From cde585d47e9ec94efdeba799157953d2d0536b10 Mon Sep 17 00:00:00 2001 From: 45coll <674148718@qq.com> Date: Wed, 27 Oct 2021 15:46:59 +0800 Subject: [PATCH] =?UTF-8?q?=E5=AE=8C=E5=96=84?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- arduino/main/main.ino | 99 +- arduino/problems and reasons.txt | 5 +- main.cpp | 428 -- python_gui/gui/main.py | 1 + 莱洛三角切割/triangle.dxf | 9328 ----------------------------- 莱洛三角切割/triangle.lcp | Bin 16753 -> 0 bytes 莱洛三角切割/wheel.dxf | 9628 ------------------------------ 莱洛三角切割/wheel.lcp | Bin 6047 -> 0 bytes 8 files changed, 72 insertions(+), 19417 deletions(-) delete mode 100644 main.cpp delete mode 100644 莱洛三角切割/triangle.dxf delete mode 100644 莱洛三角切割/triangle.lcp delete mode 100644 莱洛三角切割/wheel.dxf delete mode 100644 莱洛三角切割/wheel.lcp diff --git a/arduino/main/main.ino b/arduino/main/main.ino index e680f83..ee0985d 100644 --- a/arduino/main/main.ino +++ b/arduino/main/main.ino @@ -1,19 +1,22 @@ /** -Deng's FOC 闭环速度控制例程 测试库:SimpleFOC 2.1.1 测试硬件:灯哥开源FOC V1.0 -在串口窗口中输入:T+速度,就可以使得两个电机闭环转动 -比如让两个电机都以 10rad/s 的速度转动,则输入:T10 -在使用自己的电机时,请一定记得修改默认极对数,即 BLDCMotor(7) 中的值,设置为自己的极对数数字 -程序默认设置的供电电压为 16.8V,用其他电压供电请记得修改 voltage_power_supply , voltage_limit 变量中的值 -默认PID针对的电机是 GB6010 ,使用自己的电机需要修改PID参数,才能实现更好效果 +arduino开发环境-灯哥开源FOChttps://gitee.com/ream_d/Deng-s-foc-controller,并安装Kalman。 +FOC引脚32, 33, 25, 22 22为enable +AS5600霍尔传感器 SDA-23 SCL-5 MPU6050六轴传感器 SDA-19 SCL-18 +本程序有两种平衡方式, FLAG_V为1时使用电压控制,为0时候速度控制。电压控制时LQR参数使用K1和K2,速度控制时LQR参数使用K3和K4 +在wifi上位机窗口中输入:TA+角度,就可以修改平衡角度 +比如让平衡角度为90度,则输入:TA90,并且会存入eeprom的位置0中 注:wifi发送命令不能过快,因为每次都会保存进eeprom +在使用自己的电机时,请一定记得修改默认极对数,即 BLDCMotor(5) 中的值,设置为自己的极对数数字,磁铁数量/2 +程序默认设置的供电电压为 12V,用其他电压供电请记得修改 voltage_power_supply , voltage_limit 变量中的值 +默认PID针对的电机是 GB2204 ,使用自己的电机需要修改PID参数,才能实现更好效果 */ #include #include "Command.h" #include #include //引用以使用异步UDP #include // Source: https://github.com/TKJElectronics/KalmanFilter +#include "EEPROM.h" Kalman kalmanZ; #define gyroZ_OFF -0.19 -#define balance_voltage 10 //V /* ----IMU Data---- */ double accX, accY, accZ; @@ -42,11 +45,7 @@ unsigned int localUdpPort = 2333; //本地端口号 void wifi_print(char * s,double num); MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C); -float PID_P = 1; // -float PID_I = 0; // -float PID_D = 0; // TwoWire I2Ctwo = TwoWire(1); -PIDController angle_pid = PIDController(PID_P, PID_I, PID_D, balance_voltage * 0.7, 20000); LowPassFilter lpf_throttle{0.00}; #define FLAG_V 0 //倒立摆参数 @@ -58,21 +57,29 @@ float LQR_K2_1 = 3.49; //平衡态 float LQR_K2_2 = 0.26; // float LQR_K2_3 = 0.15; // -float LQR_K3_1 = 5.25; //平衡态 +float LQR_K3_1 = 5.25; //摇摆到平衡 float LQR_K3_2 = 3.18; // float LQR_K3_3 = 1.86; // +float LQR_K4_1 = 2.4; //摇摆到平衡 +float LQR_K4_2 = 1.5; // +float LQR_K4_3 = 1.42; // + //电机参数 BLDCMotor motor = BLDCMotor(5); BLDCDriver3PWM driver = BLDCDriver3PWM(32, 33, 25, 22); float target_velocity = 0; -float target_angle = 90; +float target_angle = 89.3; float target_voltage = 0; -float swing_up_voltage = 2; +float swing_up_voltage = 1.8; +float swing_up_angle = 18; //命令设置 Command comm; bool Motor_enable_flag = 0; -void do_TA(char* cmd) { comm.scalar(&target_angle, cmd); } +void do_TA(char* cmd) { comm.scalar(&target_angle, cmd);EEPROM.writeFloat(0, target_angle); } +void do_SV(char* cmd) { comm.scalar(&swing_up_voltage, cmd); EEPROM.writeFloat(4, swing_up_voltage); } +void do_SA(char* cmd) { comm.scalar(&swing_up_angle, cmd);EEPROM.writeFloat(8, swing_up_angle); } + void do_START(char* cmd) { wifi_flag = !wifi_flag; } void do_MOTOR(char* cmd) { @@ -82,7 +89,6 @@ void do_MOTOR(char* cmd) digitalWrite(22,LOW); Motor_enable_flag = !Motor_enable_flag; } -void do_SW(char* cmd) { comm.scalar(&swing_up_voltage, cmd); } #if FLAG_V void do_K11(char* cmd) { comm.scalar(&LQR_K1_1, cmd); } void do_K12(char* cmd) { comm.scalar(&LQR_K1_2, cmd); } @@ -91,12 +97,15 @@ void do_K21(char* cmd) { comm.scalar(&LQR_K2_1, cmd); } void do_K22(char* cmd) { comm.scalar(&LQR_K2_2, cmd); } void do_K23(char* cmd) { comm.scalar(&LQR_K2_3, cmd); } #else -void do_vp(char* cmd) { comm.scalar(&motor.PID_velocity.P, cmd); } -void do_vi(char* cmd) { comm.scalar(&motor.PID_velocity.I, cmd); } +void do_vp(char* cmd) { comm.scalar(&motor.PID_velocity.P, cmd); EEPROM.writeFloat(12, motor.PID_velocity.P);} +void do_vi(char* cmd) { comm.scalar(&motor.PID_velocity.I, cmd);EEPROM.writeFloat(16, motor.PID_velocity.I); } void do_tv(char* cmd) { comm.scalar(&target_velocity, cmd); } void do_K31(char* cmd) { comm.scalar(&LQR_K3_1, cmd); } void do_K32(char* cmd) { comm.scalar(&LQR_K3_2, cmd); } void do_K33(char* cmd) { comm.scalar(&LQR_K3_3, cmd); } +void do_K41(char* cmd) { comm.scalar(&LQR_K4_1, cmd); } +void do_K42(char* cmd) { comm.scalar(&LQR_K4_2, cmd); } +void do_K43(char* cmd) { comm.scalar(&LQR_K4_3, cmd); } #endif @@ -106,17 +115,28 @@ void onPacketCallBack(AsyncUDPPacket packet) da= (char*)(packet.data()); Serial.println(da); comm.run(da); - + EEPROM.commit(); // packet.print("reply data"); } // instantiate the commander void setup() { Serial.begin(115200); + if (!EEPROM.begin(1000)) { + Serial.println("Failed to initialise EEPROM"); + Serial.println("Restarting..."); + delay(1000); + ESP.restart(); + } + //命令设置 comm.add("TA",do_TA); comm.add("START",do_START); comm.add("MOTOR",do_MOTOR); - comm.add("SW",do_SW); + comm.add("SV",do_SV); + comm.add("SA",do_SA); + target_angle = EEPROM.readFloat(0); +swing_up_voltage = EEPROM.readFloat(4); +swing_up_angle = EEPROM.readFloat(8); #if FLAG_V comm.add("K11",do_K11); comm.add("K12",do_K12); @@ -131,6 +151,11 @@ void setup() { comm.add("K31",do_K31); comm.add("K32",do_K32); comm.add("K33",do_K33); + comm.add("K41",do_K41); + comm.add("K42",do_K42); + comm.add("K43",do_K43); + motor.PID_velocity.P = EEPROM.readFloat(12); + motor.PID_velocity.I = EEPROM.readFloat(16); #endif // kalman mpu6050 init Wire.begin(19, 18,400000);// Set I2C frequency to 400kHz @@ -200,7 +225,7 @@ void setup() { motor.controller = MotionControlType::velocity; //速度PI环设置 motor.PID_velocity.P = 0.5; - motor.PID_velocity.I = 10; + motor.PID_velocity.I = 20; #endif @@ -258,18 +283,18 @@ void loop() { gyroZangle = kalAngleZ; float pendulum_angle = constrainAngle(fmod(kalAngleZ,120)-target_angle); -// float pendulum_angle = constrainAngle((fmod(kalAngleZ * 3, 360.0) / 3.0 - target_angle) / 57.29578); -#if FLAG_V - if (abs(pendulum_angle) < 12) // if angle small enough stabilize 0.5~30°,1.5~90° +// FLAG_V为1时使用电压控制,为0时候速度控制 +#if FLAG_V + if (abs(pendulum_angle) < swing_up_angle) // if angle small enough stabilize 0.5~30°,1.5~90° { - target_voltage = controllerLQR(angle_pid(pendulum_angle), gyroZrate, motor.shaftVelocity()); + target_voltage = controllerLQR(pendulum_angle, gyroZrate, motor.shaftVelocity()); // limit the voltage set to the motor if (abs(target_voltage) > motor.voltage_limit * 0.7) target_voltage = _sign(target_voltage) * motor.voltage_limit * 0.7; } else // else do swing-up { // sets 1.5V to the motor in order to swing up - target_voltage = -_sign(gyroZrate) * 1.5; + target_voltage = -_sign(gyroZrate) * swing_up_voltage; } // set the target voltage to the motor @@ -283,9 +308,9 @@ void loop() { } #else -if (abs(pendulum_angle) < 18) // if angle small enough stabilize 0.5~30°,1.5~90° +if (abs(pendulum_angle) < swing_up_angle) // if angle small enough stabilize 0.5~30°,1.5~90° { - target_velocity = LQR_K3_1*pendulum_angle+LQR_K3_2*gyroZrate+LQR_K3_3*motor.shaftVelocity(); + target_velocity = controllerLQR(pendulum_angle, gyroZrate, motor.shaftVelocity()); if (abs(target_velocity) > 140) target_velocity = _sign(target_velocity) * 140; motor.controller = MotionControlType::velocity; @@ -348,7 +373,7 @@ double acc2rotation(double x, double y) } } -// function constraining the angle in between -pi and pi, in degrees -180 and 180 +// function constraining the angle in between -60~60 float constrainAngle(float x) { float a = 0; @@ -370,7 +395,7 @@ float controllerLQR(float p_angle, float p_vel, float m_vel) // - k = [40, 7, 0.3] // - k = [13.3, 21, 0.3] // - x = [pendulum angle, pendulum velocity, motor velocity]' - if (abs(p_angle) > 1.5) + if (abs(p_angle) > 2.5) { last_unstable_time = millis(); stable = 0; @@ -382,6 +407,7 @@ float controllerLQR(float p_angle, float p_vel, float m_vel) //Serial.println(stable); float u; +#if FLAG_V if (!stable) { u = LQR_K1_1 * p_angle + LQR_K1_2 * p_vel + LQR_K1_3 * m_vel; @@ -391,8 +417,17 @@ float controllerLQR(float p_angle, float p_vel, float m_vel) //u = LQR_K1 * p_angle + LQR_K2 * p_vel + LQR_K3 * m_vel; u = LQR_K2_1 * p_angle + LQR_K2_2 * p_vel + LQR_K2_3 * m_vel; } - - +#else + if (!stable) + { + u = LQR_K3_1 * p_angle + LQR_K3_2 * p_vel + LQR_K3_3 * m_vel; + } + else + { + //u = LQR_K1 * p_angle + LQR_K2 * p_vel + LQR_K3 * m_vel; + u = LQR_K4_1 * p_angle + LQR_K4_2 * p_vel + LQR_K4_3 * m_vel; + } +#endif return u; } void wifi_print(char * s,double num) diff --git a/arduino/problems and reasons.txt b/arduino/problems and reasons.txt index cc7a991..e865337 100644 --- a/arduino/problems and reasons.txt +++ b/arduino/problems and reasons.txt @@ -8,4 +8,7 @@ sprintf(s, "%d", 100//100תΪ10Ʊʾַ 4ǿת(const unsigned char*)ֱʹprint -atoi((char*)(packet.data())) //ʹ(char*) ǿת \ No newline at end of file +atoi((char*)(packet.data())) //ʹ(char*) ǿת + +5: udpʱ +ַĩβҪ'\0'Ϊ \ No newline at end of file diff --git a/main.cpp b/main.cpp deleted file mode 100644 index 59e36bd..0000000 --- a/main.cpp +++ /dev/null @@ -1,428 +0,0 @@ - -#include -#include -#include // Source: https://github.com/TKJElectronics/KalmanFilter -#define gyroZ_OFF -0.22 - -//#define stable_angle 178.2 -//#define stable_angle 58.8 - -//#define stable_angle 301.75 -#define stable_angle 60.0 -Kalman kalmanZ; - -/* IMU Data */ -double accX, accY, accZ; -double gyroX, gyroY, gyroZ; -int16_t tempRaw; - -double gyroZangle; // Angle calculate using the gyro only -double compAngleZ; // Calculated angle using a complementary filter -double kalAngleZ; // Calculated angle using a Kalman filter - -uint32_t timer; -uint8_t i2cData[14]; // Buffer for I2C data - -/********************************************************************************/ -#include -//#include "common/foc_utils.h" -#define swing_up_voltage 1.5 //V -#define balance_voltage 10 //V -#define min_voltage 9.5 //V -/* - #define PID_P 0 // - #define PID_I 0 // - #define PID_D 1 // - #define LQR_K1 1 // - #define LQR_K2 0 // - #define LQR_K3 0.0 // -*/ -float PID_P = 1; // -float PID_I = 0; // -float PID_D = 0; // -/* -//稳定器参数 -float LQR_K1 = 50; //摇摆到平衡 -float LQR_K2 = 2; // -float LQR_K3 = 0.30; // - -float LQR_K1_1 = 50; //平衡态 -float LQR_K2_1 = 2; // -float LQR_K3_1 = 0.15; // -*/ -//倒立摆参数 -float LQR_K1 = 200; //摇摆到平衡 -float LQR_K2 = 40; // -float LQR_K3 = 0.30; // - -float LQR_K1_1 = 200; //平衡态 -float LQR_K2_1 = 15; // -float LQR_K3_1 = 0.15; // - -/* -float LQR_K1 = 200; // -float LQR_K2 = 40; // -float LQR_K3 = 0.30; // -*/ -/*单角度稳定 - -float LQR_K1 = 80; //平衡完成 -float LQR_K2 = 15; // -float LQR_K3 = 0.15; // -*/ -float OFFSET = 0; -bool stable = 0, battery_low = 0; -uint32_t last_unstable_time; -//output=LQR_K1*PID+LQR_K2*p_vel + LQR_K3 * m_vel - -MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C); -PIDController angle_pid = PIDController(PID_P, PID_I, PID_D, balance_voltage * 0.7, 20000); -LowPassFilter lpf_throttle{0.00}; -// BLDC motor init -BLDCMotor motor = BLDCMotor(5); -// driver instance -BLDCDriver3PWM driver = BLDCDriver3PWM(9, 10, 11, 8, 3); -double rotationshift(double origin, double theta, double shift, bool y); -double acc2rotation(double x, double y); -float controllerLQR(float p_angle, float p_vel, float m_vel); -float constrainAngle(float x); - -// instantiate the commander -Commander command = Commander(Serial); -//void onp(char *cmd) { command.scalar(&PID_P, cmd); } -//void oni(char *cmd) { command.scalar(&PID_I, cmd); } -//void ond(char *cmd) { command.scalar(&PID_D, cmd); } -void onj(char *cmd) { command.scalar(&LQR_K1, cmd); } -void onk(char *cmd) { command.scalar(&LQR_K2, cmd); } -void onl(char *cmd) { command.scalar(&LQR_K3, cmd); } - -/********************************************************************************/ -void setup() -{ - Serial.begin(115200); - Wire.begin(); - - Wire.setClock(400000UL); // Set I2C frequency to 400kHz - Serial.println(((analogRead(A3) / 41.5))); - i2cData[0] = 7; // Set the sample rate to 1000Hz - 8kHz/(7+1) = 1000Hz - i2cData[1] = 0x00; // Disable FSYNC and set 260 Hz Acc filtering, 256 Hz Gyro filtering, 8 KHz sampling - i2cData[2] = 0x00; // Set Gyro Full Scale Range to ±250deg/s - i2cData[3] = 0x00; // Set Accelerometer Full Scale Range to ±2g - while (i2cWrite(0x19, i2cData, 4, false)) - ; // Write to all four registers at once - while (i2cWrite(0x6B, 0x01, true)) - ; // PLL with X axis gyroscope reference and disable sleep mode - - while (i2cRead(0x75, i2cData, 1)) - ; - if (i2cData[0] != 0x68) - { // Read "WHO_AM_I" register - Serial.print(F("Error reading sensor")); - while (1) - ; - } - - delay(100); // Wait for sensor to stabilize - - /* Set kalman and gyro starting angle */ - while (i2cRead(0x3B, i2cData, 6)) - ; - accX = (int16_t)((i2cData[0] << 8) | i2cData[1]); - accY = (int16_t)((i2cData[2] << 8) | i2cData[3]); - accZ = (int16_t)((i2cData[4] << 8) | i2cData[5]); - - // Source: http://www.freescale.com/files/sensors/doc/app_note/AN3461.pdf eq. 25 and eq. 26 - // atan2 outputs the value of -π to π (radians) - see http://en.wikipedia.org/wiki/Atan2 - // It is then converted from radians to degrees - // Eq. 25 and 26 - - double pitch = acc2rotation(accX, accY); - - kalmanZ.setAngle(pitch); - gyroZangle = pitch; - - timer = micros(); - - pinMode(4, OUTPUT); - digitalWrite(4, 1); - sensor.init(&Wire); - motor.linkSensor(&sensor); - // driver - driver.voltage_power_supply = 12; - driver.init(); - - // link the driver and the motor - motor.linkDriver(&driver); - - // aligning voltage - motor.voltage_sensor_align = 3; - - // choose FOC modulation (optional) - //motor.foc_modulation = FOCModulationType::SinePWM; - motor.foc_modulation = FOCModulationType::SpaceVectorPWM; - - // set control loop type to be used - motor.controller = MotionControlType::torque; - //motor.controller = TorqueControlType::voltage; - - motor.voltage_limit = balance_voltage; - - motor.useMonitoring(Serial); - // initialize motor - motor.init(); - // align encoder and start FOC - //motor.initFOC(4.5,Direction::CW); - //motor.initFOC(4.05, Direction::CCW); - motor.initFOC(); - //motor.initFOC(2.6492,Direction::CW); - //command.add('p', onp, "p"); - //command.add('i', oni, "i"); - //command.add('d', ond, "d"); - command.add('j', onj, "newj:"); - command.add('k', onk, "newk:"); - command.add('l', onl, "newl:"); - - digitalWrite(4, 0); -} -long loop_count = 0; -float target_voltage; -void loop() -{ - - motor.loopFOC(); - - if (loop_count++ == 10) - { - /* Update all the values */ - while (i2cRead(0x3B, i2cData, 14)) - ; - accX = (int16_t)((i2cData[0] << 8) | i2cData[1]); - accY = (int16_t)((i2cData[2] << 8) | i2cData[3]); - accZ = (int16_t)((i2cData[4] << 8) | i2cData[5]); - tempRaw = (int16_t)((i2cData[6] << 8) | i2cData[7]); - gyroX = (int16_t)((i2cData[8] << 8) | i2cData[9]); - gyroY = (int16_t)((i2cData[10] << 8) | i2cData[11]); - gyroZ = (int16_t)((i2cData[12] << 8) | i2cData[13]); - ; - - double dt = (double)(micros() - timer) / 1000000; // Calculate delta time - timer = micros(); - - // Source: http://www.freescale.com/files/sensors/doc/app_note/AN3461.pdf eq. 25 and eq. 26 - // atan2 outputs the value of -π to π (radians) - see http://en.wikipedia.org/wiki/Atan2 - // It is then converted from radians to degrees - // Eq. 25 and 26 - - double pitch = acc2rotation(accX, accY); - double gyroZrate = gyroZ / 131.0; // Convert to deg/s - - kalAngleZ = kalmanZ.getAngle(pitch, gyroZrate + gyroZ_OFF, dt); - - gyroZangle += (gyroZrate + gyroZ_OFF) * dt; - //gyroXangle += kalmanX.getRate() * dt; // Calculate gyro angle using the unbiased rate - //gyroYangle += kalmanY.getRate() * dt; - - compAngleZ = 0.93 * (compAngleZ + (gyroZrate + gyroZ_OFF) * dt) + 0.07 * pitch; - - // Reset the gyro angle when it has drifted too much - if (gyroZangle < -180 || gyroZangle > 180) - gyroZangle = kalAngleZ; - - /* Print Data */ -#if 0 // Set to 1 to activate - Serial.print(accX); Serial.print("\t"); - Serial.print(accY); Serial.print("\t"); - Serial.print(accZ); Serial.print("\t"); - - Serial.print(gyroX); Serial.print("\t"); - Serial.print(gyroY); Serial.print("\t"); - Serial.print(gyroZ); Serial.print("\t"); - - Serial.print("\t"); -#endif -#if 0 - Serial.print(pitch); - Serial.print("\t"); - Serial.print(gyroZangle); - Serial.print("\t"); - Serial.print(compAngleZ); - Serial.print("\t"); - Serial.print(kalAngleZ); - Serial.print("\t"); - - //Serial.print("\r\n"); -#endif - // calculate the pendulum angle - //LQR_K1 = analogRead(A3) / 10.0; - digitalWrite(3, 1); - //float pendulum_angle = constrainAngle(rotationshift(kalAngleZ * 3, 180.0, -180.0+OFFSET, 0.0) / 57.29578 + M_PI); - //float pendulum_angle = constrainAngle((kalAngleZ - stable_angle ) / 57.29578); - float pendulum_angle = constrainAngle((fmod(kalAngleZ * 3, 360.0) / 3.0 - stable_angle) / 57.29578); - if (abs(pendulum_angle) < 0.6) // if angle small enough stabilize 0.5~30°,1.5~90° - { - //target_voltage = controllerLQR(pendulum_angle, g.gyro.z, motor.shaftVelocity()); - - target_voltage = controllerLQR(angle_pid(pendulum_angle), gyroZrate / 57.29578, motor.shaftVelocity()); - - //digitalWrite(4, 1); - } - else // else do swing-up - { // sets 1.5V to the motor in order to swing up - target_voltage = -_sign(gyroZrate) * swing_up_voltage; - digitalWrite(4, 0); - } - - // set the target voltage to the motor - if (accZ < -13000 && ((accX * accX + accY * accY) > (14000 * 14000))) - { - motor.move(0); - } - else - { - motor.move(lpf_throttle(target_voltage)); - } - command.run(); - // restart the counter - loop_count = 0; - //Serial.print("kangle:"); - driver.voltage_power_supply = analogRead(A3) / 41.5; - //Serial.println(driver.voltage_power_supply); - if ((analogRead(A3) / 41.5) < min_voltage && !battery_low) - { - battery_low = 1; - Serial.println("battery_low!!"); - while (battery_low) - { - motor.loopFOC(); - motor.move(0); - if (millis() % 500 < 250) - digitalWrite(4, 1); - else - digitalWrite(4, 0); - } - } - //Serial.print(",fangle:"); - //Serial.print(constrainAngle(rotationshift(kalAngleZ * 3, 180.0, -180.0+OFFSET, 0.0) / 57.29578 + M_PI)); - - //Serial.println(fmod(kalAngleZ * 3, 360.0) / 3.0); - //Serial.print(",pid:"); - //Serial.println(accX); - //Serial.print(angle_pid(pendulum_angle)); - //Serial.print(",voltage:"); - //Serial.print(target_voltage); - //Serial.print(",lpf_throttle:"); - //Serial.println(lpf_throttle(target_voltage)); - //Serial.print(",E_gle:"); - //Serial.print(sensor.getAngle()); - //Serial.print(",vel:"); - //Serial.println(sensor.getVelocity()); - } - - - - -} - -// function constraining the angle in between -pi and pi, in degrees -180 and 180 -float constrainAngle(float x) -{ - x = fmod(x + M_PI, _2PI); - if (x < 0) - x += _2PI; - return x - M_PI; -} -// LQR stabilization controller functions -// calculating the voltage that needs to be set to the motor in order to stabilize the pendulum -float controllerLQR(float p_angle, float p_vel, float m_vel) -{ - // if angle controllable - // calculate the control law - // LQR controller u = k*x - // - k = [40, 7, 0.3] - // - k = [13.3, 21, 0.3] - // - x = [pendulum angle, pendulum velocity, motor velocity]' - if (abs(p_angle) > 0.05) - { - last_unstable_time = millis(); - stable = 0; - digitalWrite(4, 0); - } - if ((millis() - last_unstable_time) > 1000) - { - stable = 1; - digitalWrite(4, 1); - } - - //Serial.println(stable); - float u; - if (!stable) - { - u = LQR_K1 * p_angle + LQR_K2 * p_vel + LQR_K3 * m_vel; - } - else - { - //u = LQR_K1 * p_angle + LQR_K2 * p_vel + LQR_K3 * m_vel; - u = LQR_K1_1 * p_angle + LQR_K2_1 * p_vel + LQR_K3_1 * m_vel; - } - - // limit the voltage set to the motor - if (abs(u) > motor.voltage_limit * 0.7) - u = _sign(u) * motor.voltage_limit * 0.7; - - return u; -} -/* mpu6050加速度转换为角度 - acc2rotation(ax, ay) - acc2rotation(az, ay) */ -double acc2rotation(double x, double y) -{ - if (y < 0) - { - return atan(x / y) / 1.570796 * 90 + 180; - } - else if (x < 0) - { - return (atan(x / y) / 1.570796 * 90 + 360); - } - else - { - return (atan(x / y) / 1.570796 * 90); - } -} - -/* mpu6050加速度转换为角度 - rotationshift(original angle,+θ,shiftθ,0 is normal,1 is reverse) - rotationshift(0,30)=30 - rotationshift(20,30)=50 - rotationshift(0,30,1)=330 - rotationshift(20,30,1)=310 - rotationshift(0,0,-180,0)=-180 -*/ -double rotationshift(double origin, double theta, double shift = 0, bool y = false) -{ - static float origin_old; - if (abs(origin - origin_old) > 0.1) - origin_old += _sign(origin - origin_old) * 0.01; - else - origin_old = origin; - - if (y == 0) - { - if (origin + theta > 360) - return origin + theta - 360 + shift; - else - { - return origin + theta + shift; - } - } - else - { - - if (-(origin + theta) + 360 < 0) - return -(origin + theta) + 360 + 360 + shift; - else - { - return -(origin + theta) + 360 + shift; - } - } -} diff --git a/python_gui/gui/main.py b/python_gui/gui/main.py index f4ec752..221c1f2 100644 --- a/python_gui/gui/main.py +++ b/python_gui/gui/main.py @@ -118,6 +118,7 @@ class MyWindow(QMainWindow, Ui_MainWindow): recv_data = recv_data[:-1] recv_data = recv_data.split(',') """处理接受的信息""" + # recv_data = [40,50,60] for i, data in enumerate(recv_data): self.re_item.append(''.join(re.split(r'[^A-Za-z]', data))) print(self.re_item) diff --git a/莱洛三角切割/triangle.dxf b/莱洛三角切割/triangle.dxf deleted file mode 100644 index 1bfb752..0000000 --- a/莱洛三角切割/triangle.dxf +++ /dev/null @@ -1,9328 +0,0 @@ -999 -dxflib 3.17.0.0 - 0 -SECTION - 2 -HEADER - 9 -$ACADVER - 1 -AC1015 - 9 -$HANDSEED - 5 -FFFF - 9 -$INSUNITS - 70 -4 - 9 -$DIMEXE - 40 -1.25 - 9 -$TEXTSTYLE - 7 -Standard - 9 -$LIMMIN - 10 -0.0 - 20 -0.0 - 0 -ENDSEC - 0 -SECTION - 2 -TABLES - 0 -TABLE - 2 -VPORT - 5 -8 -100 -AcDbSymbolTable - 70 -1 - 0 -VPORT - 5 -30 -100 -AcDbSymbolTableRecord -100 -AcDbViewportTableRecord - 2 -*Active - 70 -0 - 10 -0.0 - 20 -0.0 - 11 -1.0 - 21 -1.0 - 12 -286.30555555555549 - 22 -148.5 - 13 -0.0 - 23 -0.0 - 14 -10.0 - 24 -10.0 - 15 -10.0 - 25 -10.0 - 16 -0.0 - 26 -0.0 - 36 -1.0 - 17 -0.0 - 27 -0.0 - 37 -0.0 - 40 -297.0 - 41 -1.92798353909465 - 42 -50.0 - 43 -0.0 - 44 -0.0 - 50 -0.0 - 51 -0.0 - 71 -0 - 72 -100 - 73 -1 - 74 -3 - 75 -1 - 76 -1 - 77 -0 - 78 -0 -281 -0 - 65 -1 -110 -0.0 -120 -0.0 -130 -0.0 -111 -1.0 -121 -0.0 -131 -0.0 -112 -0.0 -122 -1.0 -132 -0.0 - 79 -0 -146 -0.0 - 0 -ENDTAB - 0 -TABLE - 2 -LTYPE - 5 -5 -100 -AcDbSymbolTable - 70 -25 - 0 -LTYPE - 5 -14 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BYBLOCK - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -15 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BYLAYER - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -16 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -CONTINUOUS - 70 -0 - 3 -Solid line - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -31 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -ACAD_ISO02W100 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -32 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -ACAD_ISO03W100 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -33 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -ACAD_ISO04W100 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -34 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -ACAD_ISO05W100 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -35 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BORDER - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -36 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BORDER2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -37 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BORDERX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -38 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -CENTER - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -39 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -CENTER2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3A -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -CENTERX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3B -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHDOT - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3C -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHDOT2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3D -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHDOTX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3E -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHED - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3F -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHED2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -40 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHEDX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -41 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DIVIDE - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -42 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DIVIDE2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -43 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DIVIDEX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -44 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DOT - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -45 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DOT2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -46 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DOTX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -ENDTAB - 0 -TABLE - 2 -LAYER - 5 -2 -100 -AcDbSymbolTable - 70 -1 - 0 -LAYER - 5 -10 -100 -AcDbSymbolTableRecord -100 -AcDbLayerTableRecord - 2 -0 - 70 -0 - 62 --1 -420 -0 - 6 -CONTINUOUS -370 -1 -390 -F - 0 -ENDTAB - 0 -STYLE - 5 -47 -100 -AcDbSymbolTableRecord -100 -AcDbTextStyleTableRecord - 2 - - 70 -0 - 40 -0.0 - 41 -0.0 - 50 -0.0 - 71 -0 - 42 -0.0 - 3 - - 4 - -1001 -ACAD -1000 - -1071 -0 - 0 -TABLE - 2 -VIEW - 5 -6 -100 -AcDbSymbolTable - 70 -0 - 0 -ENDTAB - 0 -TABLE - 2 -UCS - 5 -7 -100 -AcDbSymbolTable - 70 -0 - 0 -ENDTAB - 0 -TABLE - 2 -APPID - 5 -9 -100 -AcDbSymbolTable - 70 -1 - 0 -APPID - 5 -12 -100 -AcDbSymbolTableRecord -100 -AcDbRegAppTableRecord - 2 -ACAD - 70 -0 - 0 -ENDTAB - 0 -TABLE - 2 -DIMSTYLE - 5 -A -100 -AcDbSymbolTable - 70 -1 -100 -AcDbDimStyleTable - 71 -0 - 0 -DIMSTYLE -105 -27 -100 -AcDbSymbolTableRecord -100 -AcDbDimStyleTableRecord - 2 -Standard - 41 -1.0 - 42 -1.0 - 43 -3.75 - 44 -1.0 - 70 -0 - 73 -0 - 74 -0 - 77 -1 - 78 -8 -140 -1.0 -141 -2.5 -143 -0.03937007874016 -147 -1.0 -171 -3 -172 -1 -271 -2 -272 -2 -274 -3 -278 -44 -283 -0 -284 -8 -340 -3A1A5DA9 - 0 -ENDTAB - 0 -TABLE - 2 -BLOCK_RECORD - 5 -1 -100 -AcDbSymbolTable - 70 -1 - 0 -BLOCK_RECORD - 5 -1F -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -*Model_Space -340 -22 - 0 -BLOCK_RECORD - 5 -1B -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -*Paper_Space -340 -1E - 0 -BLOCK_RECORD - 5 -23 -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -*Paper_Space0 -340 -26 - 0 -BLOCK_RECORD - 5 -48 -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -myblock1 -340 -0 - 0 -BLOCK_RECORD - 5 -49 -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -myblock2 -340 -0 - 0 -ENDTAB - 0 -ENDSEC - 0 -SECTION - 2 -BLOCKS - 0 -BLOCK - 5 -20 -100 -AcDbEntity - 8 -0 -100 -AcDbBlockBegin - 2 -*Model_Space - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -*Model_Space - 1 - - 0 -ENDBLK - 5 -21 -100 -AcDbEntity - 8 -0 -100 -AcDbBlockEnd - 0 -BLOCK - 5 -1C -100 -AcDbEntity - 67 -1 - 8 -0 -100 -AcDbBlockBegin - 2 -*Paper_Space - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -*Paper_Space - 1 - - 0 -ENDBLK - 5 -1D -100 -AcDbEntity - 67 -1 - 8 -0 -100 -AcDbBlockEnd - 0 -BLOCK - 5 -24 -100 -AcDbEntity - 8 -0 -100 -AcDbBlockBegin - 2 -*Paper_Space0 - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -*Paper_Space0 - 1 - - 0 -ENDBLK - 5 -25 -100 -AcDbEntity - 8 -0 -100 -AcDbBlockEnd - 0 -BLOCK - 5 -4A -100 -AcDbEntity - 8 -0 -100 -AcDbBlockBegin - 2 -myblock1 - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -myblock1 - 1 - - 0 -ENDBLK - 5 -4B -100 -AcDbEntity - 8 -0 -100 -AcDbBlockEnd - 0 -BLOCK - 5 -4C -100 -AcDbEntity - 8 -0 -100 -AcDbBlockBegin - 2 -myblock2 - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -myblock2 - 1 - - 0 -ENDBLK - 5 -4D -100 -AcDbEntity - 8 -0 -100 -AcDbBlockEnd - 0 -ENDSEC - 0 -SECTION - 2 -ENTITIES - 0 -LWPOLYLINE - 5 -4E -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -74 - 70 -0 - 10 -444.0 - 20 -289.83029174804687 - 30 -0.0 - 10 -444.00750732421875 - 20 -289.52279663085937 - 30 -0.0 - 10 -444.02999877929687 - 20 -289.21780395507812 - 30 -0.0 - 10 -444.12249755859375 - 20 -288.62030029296875 - 30 -0.0 - 10 -444.26998901367187 - 20 -288.04531860351562 - 30 -0.0 - 10 -444.47250366210937 - 20 -287.49530029296875 - 30 -0.0 - 10 -444.72500610351562 - 20 -286.97030639648437 - 30 -0.0 - 10 -445.02499389648437 - 20 -286.47531127929687 - 30 -0.0 - 10 -445.3699951171875 - 20 -286.01528930664062 - 30 -0.0 - 10 -445.75750732421875 - 20 -285.58779907226562 - 30 -0.0 - 10 -446.1824951171875 - 20 -285.2003173828125 - 30 -0.0 - 10 -446.64498901367187 - 20 -284.85531616210937 - 30 -0.0 - 10 -447.1400146484375 - 20 -284.5552978515625 - 30 -0.0 - 10 -447.66500854492187 - 20 -284.30279541015625 - 30 -0.0 - 10 -448.21499633789062 - 20 -284.10031127929687 - 30 -0.0 - 10 -448.79000854492187 - 20 -283.95278930664062 - 30 -0.0 - 10 -449.38751220703125 - 20 -283.86029052734375 - 30 -0.0 - 10 -449.69000244140625 - 20 -283.83779907226562 - 30 -0.0 - 10 -450.0 - 20 -283.83029174804687 - 30 -0.0 - 10 -450.3074951171875 - 20 -283.83779907226562 - 30 -0.0 - 10 -450.61251831054687 - 20 -283.86029052734375 - 30 -0.0 - 10 -451.20999145507812 - 20 -283.95278930664062 - 30 -0.0 - 10 -451.78500366210937 - 20 -284.10031127929687 - 30 -0.0 - 10 -452.33499145507812 - 20 -284.30279541015625 - 30 -0.0 - 10 -452.86001586914062 - 20 -284.5552978515625 - 30 -0.0 - 10 -453.35501098632812 - 20 -284.85531616210937 - 30 -0.0 - 10 -453.81500244140625 - 20 -285.2003173828125 - 30 -0.0 - 10 -454.24249267578125 - 20 -285.58779907226562 - 30 -0.0 - 10 -454.6300048828125 - 20 -286.01528930664062 - 30 -0.0 - 10 -454.97500610351562 - 20 -286.47531127929687 - 30 -0.0 - 10 -455.27499389648437 - 20 -286.97030639648437 - 30 -0.0 - 10 -455.52749633789062 - 20 -287.49530029296875 - 30 -0.0 - 10 -455.73001098632812 - 20 -288.04531860351562 - 30 -0.0 - 10 -455.87750244140625 - 20 -288.62030029296875 - 30 -0.0 - 10 -455.96749877929687 - 20 -289.21530151367187 - 30 -0.0 - 10 -455.99249267578125 - 20 -289.52029418945312 - 30 -0.0 - 10 -456.0 - 20 -289.83029174804687 - 30 -0.0 - 10 -455.99249267578125 - 20 -290.14028930664062 - 30 -0.0 - 10 -455.97000122070312 - 20 -290.44281005859375 - 30 -0.0 - 10 -455.87750244140625 - 20 -291.04031372070312 - 30 -0.0 - 10 -455.73001098632812 - 20 -291.61529541015625 - 30 -0.0 - 10 -455.52749633789062 - 20 -292.16531372070312 - 30 -0.0 - 10 -455.27499389648437 - 20 -292.6903076171875 - 30 -0.0 - 10 -454.97500610351562 - 20 -293.185302734375 - 30 -0.0 - 10 -454.6300048828125 - 20 -293.64779663085937 - 30 -0.0 - 10 -454.24249267578125 - 20 -294.07281494140625 - 30 -0.0 - 10 -453.81500244140625 - 20 -294.46029663085937 - 30 -0.0 - 10 -453.35501098632812 - 20 -294.8052978515625 - 30 -0.0 - 10 -452.86001586914062 - 20 -295.10531616210937 - 30 -0.0 - 10 -452.33499145507812 - 20 -295.35781860351562 - 30 -0.0 - 10 -451.78250122070312 - 20 -295.560302734375 - 30 -0.0 - 10 -451.20748901367187 - 20 -295.70779418945312 - 30 -0.0 - 10 -450.61251831054687 - 20 -295.80029296875 - 30 -0.0 - 10 -450.3074951171875 - 20 -295.82281494140625 - 30 -0.0 - 10 -450.0 - 20 -295.83029174804688 - 30 -0.0 - 10 -449.69000244140625 - 20 -295.82281494140625 - 30 -0.0 - 10 -449.38751220703125 - 20 -295.80029296875 - 30 -0.0 - 10 -448.79000854492187 - 20 -295.70779418945312 - 30 -0.0 - 10 -448.21499633789062 - 20 -295.560302734375 - 30 -0.0 - 10 -447.66500854492187 - 20 -295.35781860351562 - 30 -0.0 - 10 -447.1400146484375 - 20 -295.10531616210937 - 30 -0.0 - 10 -446.64498901367187 - 20 -294.8052978515625 - 30 -0.0 - 10 -446.1824951171875 - 20 -294.46029663085937 - 30 -0.0 - 10 -445.75750732421875 - 20 -294.07281494140625 - 30 -0.0 - 10 -445.3699951171875 - 20 -293.64779663085937 - 30 -0.0 - 10 -445.02499389648437 - 20 -293.185302734375 - 30 -0.0 - 10 -444.72500610351562 - 20 -292.6903076171875 - 30 -0.0 - 10 -444.47250366210937 - 20 -292.16531372070312 - 30 -0.0 - 10 -444.26998901367187 - 20 -291.61529541015625 - 30 -0.0 - 10 -444.12249755859375 - 20 -291.04031372070312 - 30 -0.0 - 10 -444.02999877929687 - 20 -290.44281005859375 - 30 -0.0 - 10 -444.00750732421875 - 20 -290.14028930664062 - 30 -0.0 - 10 -444.0 - 20 -289.83029174804687 - 30 -0.0 - 10 -444.0 - 20 -289.83029174804687 - 30 -0.0 - 0 -LWPOLYLINE - 5 -4F -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -34 - 70 -0 - 10 -445.09756469726562 - 20 -297.08282470703125 - 30 -0.0 - 10 -445.11508178710937 - 20 -296.90032958984375 - 30 -0.0 - 10 -445.16757202148437 - 20 -296.73284912109375 - 30 -0.0 - 10 -445.25006103515625 - 20 -296.580322265625 - 30 -0.0 - 10 -445.36007690429687 - 20 -296.44534301757812 - 30 -0.0 - 10 -445.49505615234375 - 20 -296.3353271484375 - 30 -0.0 - 10 -445.64755249023437 - 20 -296.25283813476562 - 30 -0.0 - 10 -445.8150634765625 - 20 -296.20034790039062 - 30 -0.0 - 10 -445.99755859375 - 20 -296.18283081054687 - 30 -0.0 - 10 -446.1800537109375 - 20 -296.20034790039062 - 30 -0.0 - 10 -446.34756469726562 - 20 -296.25283813476562 - 30 -0.0 - 10 -446.50006103515625 - 20 -296.3353271484375 - 30 -0.0 - 10 -446.63507080078125 - 20 -296.44534301757812 - 30 -0.0 - 10 -446.74505615234375 - 20 -296.580322265625 - 30 -0.0 - 10 -446.82757568359375 - 20 -296.73284912109375 - 30 -0.0 - 10 -446.88006591796875 - 20 -296.90032958984375 - 30 -0.0 - 10 -446.89755249023437 - 20 -297.08282470703125 - 30 -0.0 - 10 -446.88006591796875 - 20 -297.26531982421875 - 30 -0.0 - 10 -446.82757568359375 - 20 -297.43283081054687 - 30 -0.0 - 10 -446.74505615234375 - 20 -297.5853271484375 - 30 -0.0 - 10 -446.63507080078125 - 20 -297.7203369140625 - 30 -0.0 - 10 -446.50006103515625 - 20 -297.830322265625 - 30 -0.0 - 10 -446.34756469726562 - 20 -297.912841796875 - 30 -0.0 - 10 -446.1800537109375 - 20 -297.96533203125 - 30 -0.0 - 10 -445.99755859375 - 20 -297.98284912109375 - 30 -0.0 - 10 -445.8150634765625 - 20 -297.96533203125 - 30 -0.0 - 10 -445.64755249023437 - 20 -297.912841796875 - 30 -0.0 - 10 -445.49505615234375 - 20 -297.830322265625 - 30 -0.0 - 10 -445.36007690429687 - 20 -297.7203369140625 - 30 -0.0 - 10 -445.25006103515625 - 20 -297.5853271484375 - 30 -0.0 - 10 -445.16757202148437 - 20 -297.43283081054687 - 30 -0.0 - 10 -445.11508178710937 - 20 -297.26531982421875 - 30 -0.0 - 10 -445.09756469726562 - 20 -297.08282470703125 - 30 -0.0 - 10 -445.09756469726562 - 20 -297.08282470703125 - 30 -0.0 - 0 -LWPOLYLINE - 5 -50 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -34 - 70 -0 - 10 -453.09756469726562 - 20 -297.08282470703125 - 30 -0.0 - 10 -453.11508178710937 - 20 -296.90032958984375 - 30 -0.0 - 10 -453.16757202148437 - 20 -296.73284912109375 - 30 -0.0 - 10 -453.25006103515625 - 20 -296.580322265625 - 30 -0.0 - 10 -453.36007690429687 - 20 -296.44534301757812 - 30 -0.0 - 10 -453.49505615234375 - 20 -296.3353271484375 - 30 -0.0 - 10 -453.64755249023437 - 20 -296.25283813476562 - 30 -0.0 - 10 -453.8150634765625 - 20 -296.20034790039062 - 30 -0.0 - 10 -453.99755859375 - 20 -296.18283081054687 - 30 -0.0 - 10 -454.1800537109375 - 20 -296.20034790039062 - 30 -0.0 - 10 -454.34756469726562 - 20 -296.25283813476562 - 30 -0.0 - 10 -454.50006103515625 - 20 -296.3353271484375 - 30 -0.0 - 10 -454.63507080078125 - 20 -296.44534301757812 - 30 -0.0 - 10 -454.74505615234375 - 20 -296.580322265625 - 30 -0.0 - 10 -454.82757568359375 - 20 -296.73284912109375 - 30 -0.0 - 10 -454.88006591796875 - 20 -296.90032958984375 - 30 -0.0 - 10 -454.89755249023437 - 20 -297.08282470703125 - 30 -0.0 - 10 -454.88006591796875 - 20 -297.26531982421875 - 30 -0.0 - 10 -454.82757568359375 - 20 -297.43283081054687 - 30 -0.0 - 10 -454.74505615234375 - 20 -297.5853271484375 - 30 -0.0 - 10 -454.63507080078125 - 20 -297.7203369140625 - 30 -0.0 - 10 -454.50006103515625 - 20 -297.830322265625 - 30 -0.0 - 10 -454.34756469726562 - 20 -297.912841796875 - 30 -0.0 - 10 -454.1800537109375 - 20 -297.96533203125 - 30 -0.0 - 10 -453.99755859375 - 20 -297.98284912109375 - 30 -0.0 - 10 -453.8150634765625 - 20 -297.96533203125 - 30 -0.0 - 10 -453.64755249023437 - 20 -297.912841796875 - 30 -0.0 - 10 -453.49505615234375 - 20 -297.830322265625 - 30 -0.0 - 10 -453.36007690429687 - 20 -297.7203369140625 - 30 -0.0 - 10 -453.25006103515625 - 20 -297.5853271484375 - 30 -0.0 - 10 -453.16757202148437 - 20 -297.43283081054687 - 30 -0.0 - 10 -453.11508178710937 - 20 -297.26531982421875 - 30 -0.0 - 10 -453.09756469726562 - 20 -297.08282470703125 - 30 -0.0 - 10 -453.09756469726562 - 20 -297.08282470703125 - 30 -0.0 - 0 -LWPOLYLINE - 5 -51 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -34 - 70 -0 - 10 -445.10006713867187 - 20 -282.58779907226562 - 30 -0.0 - 10 -445.1175537109375 - 20 -282.40530395507812 - 30 -0.0 - 10 -445.17007446289062 - 20 -282.23779296875 - 30 -0.0 - 10 -445.2525634765625 - 20 -282.08529663085937 - 30 -0.0 - 10 -445.36257934570312 - 20 -281.9503173828125 - 30 -0.0 - 10 -445.49505615234375 - 20 -281.84030151367187 - 30 -0.0 - 10 -445.64755249023437 - 20 -281.7578125 - 30 -0.0 - 10 -445.81756591796875 - 20 -281.70529174804687 - 30 -0.0 - 10 -445.99755859375 - 20 -281.68780517578125 - 30 -0.0 - 10 -446.1800537109375 - 20 -281.70529174804687 - 30 -0.0 - 10 -446.34756469726562 - 20 -281.7578125 - 30 -0.0 - 10 -446.50006103515625 - 20 -281.84030151367187 - 30 -0.0 - 10 -446.63507080078125 - 20 -281.9503173828125 - 30 -0.0 - 10 -446.74505615234375 - 20 -282.08529663085937 - 30 -0.0 - 10 -446.82757568359375 - 20 -282.23779296875 - 30 -0.0 - 10 -446.88006591796875 - 20 -282.40530395507812 - 30 -0.0 - 10 -446.89755249023437 - 20 -282.58779907226562 - 30 -0.0 - 10 -446.88006591796875 - 20 -282.76779174804687 - 30 -0.0 - 10 -446.82757568359375 - 20 -282.93780517578125 - 30 -0.0 - 10 -446.74505615234375 - 20 -283.09030151367187 - 30 -0.0 - 10 -446.63507080078125 - 20 -283.22280883789062 - 30 -0.0 - 10 -446.50006103515625 - 20 -283.33279418945312 - 30 -0.0 - 10 -446.34756469726562 - 20 -283.41781616210937 - 30 -0.0 - 10 -446.1800537109375 - 20 -283.47030639648437 - 30 -0.0 - 10 -445.99755859375 - 20 -283.48779296875 - 30 -0.0 - 10 -445.81756591796875 - 20 -283.47030639648437 - 30 -0.0 - 10 -445.64755249023437 - 20 -283.41781616210937 - 30 -0.0 - 10 -445.49505615234375 - 20 -283.33279418945312 - 30 -0.0 - 10 -445.36257934570312 - 20 -283.22280883789062 - 30 -0.0 - 10 -445.2525634765625 - 20 -283.09030151367187 - 30 -0.0 - 10 -445.17007446289062 - 20 -282.93780517578125 - 30 -0.0 - 10 -445.1175537109375 - 20 -282.76779174804687 - 30 -0.0 - 10 -445.10006713867187 - 20 -282.58779907226562 - 30 -0.0 - 10 -445.10006713867187 - 20 -282.58779907226562 - 30 -0.0 - 0 -LWPOLYLINE - 5 -52 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -34 - 70 -0 - 10 -453.09506225585937 - 20 -282.58529663085937 - 30 -0.0 - 10 -453.11257934570312 - 20 -282.40280151367187 - 30 -0.0 - 10 -453.16506958007812 - 20 -282.23529052734375 - 30 -0.0 - 10 -453.24755859375 - 20 -282.08279418945312 - 30 -0.0 - 10 -453.35757446289062 - 20 -281.94781494140625 - 30 -0.0 - 10 -453.4925537109375 - 20 -281.83779907226562 - 30 -0.0 - 10 -453.64508056640625 - 20 -281.75531005859375 - 30 -0.0 - 10 -453.81256103515625 - 20 -281.70278930664062 - 30 -0.0 - 10 -453.99505615234375 - 20 -281.685302734375 - 30 -0.0 - 10 -454.17758178710937 - 20 -281.70278930664062 - 30 -0.0 - 10 -454.34506225585937 - 20 -281.75531005859375 - 30 -0.0 - 10 -454.49755859375 - 20 -281.83779907226562 - 30 -0.0 - 10 -454.632568359375 - 20 -281.94781494140625 - 30 -0.0 - 10 -454.7425537109375 - 20 -282.08279418945312 - 30 -0.0 - 10 -454.8250732421875 - 20 -282.23529052734375 - 30 -0.0 - 10 -454.8775634765625 - 20 -282.40280151367187 - 30 -0.0 - 10 -454.89508056640625 - 20 -282.58529663085937 - 30 -0.0 - 10 -454.8775634765625 - 20 -282.76779174804687 - 30 -0.0 - 10 -454.8250732421875 - 20 -282.935302734375 - 30 -0.0 - 10 -454.7425537109375 - 20 -283.08779907226562 - 30 -0.0 - 10 -454.632568359375 - 20 -283.22280883789062 - 30 -0.0 - 10 -454.49755859375 - 20 -283.33279418945312 - 30 -0.0 - 10 -454.34506225585937 - 20 -283.41531372070312 - 30 -0.0 - 10 -454.17758178710937 - 20 -283.46780395507812 - 30 -0.0 - 10 -453.99505615234375 - 20 -283.48529052734375 - 30 -0.0 - 10 -453.81256103515625 - 20 -283.46780395507812 - 30 -0.0 - 10 -453.64508056640625 - 20 -283.41531372070312 - 30 -0.0 - 10 -453.4925537109375 - 20 -283.33279418945312 - 30 -0.0 - 10 -453.35757446289062 - 20 -283.22280883789062 - 30 -0.0 - 10 -453.24755859375 - 20 -283.08779907226562 - 30 -0.0 - 10 -453.16506958007812 - 20 -282.935302734375 - 30 -0.0 - 10 -453.11257934570312 - 20 -282.76779174804687 - 30 -0.0 - 10 -453.09506225585937 - 20 -282.58529663085937 - 30 -0.0 - 10 -453.09506225585937 - 20 -282.58529663085937 - 30 -0.0 - 0 -LWPOLYLINE - 5 -53 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -66 - 70 -0 - 10 -451.24755859375 - 20 -277.6378173828125 - 30 -0.0 - 10 -451.3675537109375 - 20 -277.77029418945312 - 30 -0.0 - 10 -451.47256469726562 - 20 -277.91281127929687 - 30 -0.0 - 10 -451.56005859375 - 20 -278.060302734375 - 30 -0.0 - 10 -451.632568359375 - 20 -278.21530151367187 - 30 -0.0 - 10 -451.68756103515625 - 20 -278.3778076171875 - 30 -0.0 - 10 -451.72756958007813 - 20 -278.54031372070313 - 30 -0.0 - 10 -451.7525634765625 - 20 -278.70779418945312 - 30 -0.0 - 10 -451.76007080078125 - 20 -278.87530517578125 - 30 -0.0 - 10 -451.7525634765625 - 20 -279.04281616210937 - 30 -0.0 - 10 -451.72756958007813 - 20 -279.21029663085937 - 30 -0.0 - 10 -451.68756103515625 - 20 -279.372802734375 - 30 -0.0 - 10 -451.632568359375 - 20 -279.53530883789062 - 30 -0.0 - 10 -451.56005859375 - 20 -279.6903076171875 - 30 -0.0 - 10 -451.47256469726562 - 20 -279.83779907226562 - 30 -0.0 - 10 -451.3675537109375 - 20 -279.98031616210937 - 30 -0.0 - 10 -451.24755859375 - 20 -280.11279296875 - 30 -0.0 - 10 -451.11508178710937 - 20 -280.23281860351562 - 30 -0.0 - 10 -450.97256469726562 - 20 -280.33779907226562 - 30 -0.0 - 10 -450.82257080078125 - 20 -280.42529296875 - 30 -0.0 - 10 -450.66757202148437 - 20 -280.497802734375 - 30 -0.0 - 10 -450.507568359375 - 20 -280.55279541015625 - 30 -0.0 - 10 -450.34255981445312 - 20 -280.59280395507812 - 30 -0.0 - 10 -450.17758178710937 - 20 -280.6177978515625 - 30 -0.0 - 10 -450.01007080078125 - 20 -280.62530517578125 - 30 -0.0 - 10 -449.84255981445312 - 20 -280.6177978515625 - 30 -0.0 - 10 -449.67507934570312 - 20 -280.59280395507812 - 30 -0.0 - 10 -449.51007080078125 - 20 -280.55279541015625 - 30 -0.0 - 10 -449.35006713867187 - 20 -280.497802734375 - 30 -0.0 - 10 -449.195068359375 - 20 -280.42529296875 - 30 -0.0 - 10 -449.04757690429687 - 20 -280.33779907226562 - 30 -0.0 - 10 -448.90505981445312 - 20 -280.23281860351562 - 30 -0.0 - 10 -448.77255249023437 - 20 -280.11279296875 - 30 -0.0 - 10 -448.65255737304687 - 20 -279.98031616210937 - 30 -0.0 - 10 -448.54757690429687 - 20 -279.83779907226562 - 30 -0.0 - 10 -448.46005249023437 - 20 -279.6903076171875 - 30 -0.0 - 10 -448.3875732421875 - 20 -279.53530883789062 - 30 -0.0 - 10 -448.33258056640625 - 20 -279.372802734375 - 30 -0.0 - 10 -448.29257202148437 - 20 -279.21029663085937 - 30 -0.0 - 10 -448.267578125 - 20 -279.04281616210937 - 30 -0.0 - 10 -448.26007080078125 - 20 -278.87530517578125 - 30 -0.0 - 10 -448.267578125 - 20 -278.70779418945312 - 30 -0.0 - 10 -448.29257202148437 - 20 -278.54031372070313 - 30 -0.0 - 10 -448.33258056640625 - 20 -278.3778076171875 - 30 -0.0 - 10 -448.3875732421875 - 20 -278.21530151367187 - 30 -0.0 - 10 -448.46005249023437 - 20 -278.060302734375 - 30 -0.0 - 10 -448.54757690429687 - 20 -277.91281127929687 - 30 -0.0 - 10 -448.65255737304687 - 20 -277.77029418945312 - 30 -0.0 - 10 -448.77255249023437 - 20 -277.6378173828125 - 30 -0.0 - 10 -448.90505981445312 - 20 -277.51779174804687 - 30 -0.0 - 10 -449.04757690429687 - 20 -277.41281127929687 - 30 -0.0 - 10 -449.195068359375 - 20 -277.3253173828125 - 30 -0.0 - 10 -449.35006713867187 - 20 -277.2528076171875 - 30 -0.0 - 10 -449.51007080078125 - 20 -277.19781494140625 - 30 -0.0 - 10 -449.67507934570312 - 20 -277.15780639648438 - 30 -0.0 - 10 -449.84255981445312 - 20 -277.1328125 - 30 -0.0 - 10 -450.01007080078125 - 20 -277.12530517578125 - 30 -0.0 - 10 -450.17758178710937 - 20 -277.1328125 - 30 -0.0 - 10 -450.34255981445312 - 20 -277.15780639648438 - 30 -0.0 - 10 -450.507568359375 - 20 -277.19781494140625 - 30 -0.0 - 10 -450.66757202148437 - 20 -277.2528076171875 - 30 -0.0 - 10 -450.82257080078125 - 20 -277.3253173828125 - 30 -0.0 - 10 -450.97256469726562 - 20 -277.41281127929687 - 30 -0.0 - 10 -451.11508178710937 - 20 -277.51779174804687 - 30 -0.0 - 10 -451.24755859375 - 20 -277.6378173828125 - 30 -0.0 - 10 -451.24755859375 - 20 -277.6378173828125 - 30 -0.0 - 0 -LWPOLYLINE - 5 -54 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -66 - 70 -0 - 10 -440.28756713867187 - 20 -288.59780883789062 - 30 -0.0 - 10 -440.40756225585937 - 20 -288.73031616210937 - 30 -0.0 - 10 -440.5125732421875 - 20 -288.872802734375 - 30 -0.0 - 10 -440.60006713867187 - 20 -289.02029418945312 - 30 -0.0 - 10 -440.67257690429688 - 20 -289.17529296875 - 30 -0.0 - 10 -440.72756958007812 - 20 -289.33779907226562 - 30 -0.0 - 10 -440.767578125 - 20 -289.50030517578125 - 30 -0.0 - 10 -440.79257202148437 - 20 -289.66781616210937 - 30 -0.0 - 10 -440.80007934570312 - 20 -289.83529663085937 - 30 -0.0 - 10 -440.79257202148437 - 20 -290.0028076171875 - 30 -0.0 - 10 -440.767578125 - 20 -290.17031860351562 - 30 -0.0 - 10 -440.72756958007812 - 20 -290.33279418945312 - 30 -0.0 - 10 -440.67257690429688 - 20 -290.49530029296875 - 30 -0.0 - 10 -440.60006713867187 - 20 -290.65029907226562 - 30 -0.0 - 10 -440.5125732421875 - 20 -290.79779052734375 - 30 -0.0 - 10 -440.40756225585937 - 20 -290.9403076171875 - 30 -0.0 - 10 -440.28756713867187 - 20 -291.07281494140625 - 30 -0.0 - 10 -440.15505981445312 - 20 -291.19281005859375 - 30 -0.0 - 10 -440.0125732421875 - 20 -291.29779052734375 - 30 -0.0 - 10 -439.86257934570312 - 20 -291.38531494140625 - 30 -0.0 - 10 -439.70758056640625 - 20 -291.45779418945312 - 30 -0.0 - 10 -439.54757690429687 - 20 -291.5128173828125 - 30 -0.0 - 10 -439.382568359375 - 20 -291.55279541015625 - 30 -0.0 - 10 -439.21755981445312 - 20 -291.57778930664062 - 30 -0.0 - 10 -439.05007934570312 - 20 -291.58529663085937 - 30 -0.0 - 10 -438.882568359375 - 20 -291.57778930664062 - 30 -0.0 - 10 -438.71505737304687 - 20 -291.55279541015625 - 30 -0.0 - 10 -438.55007934570312 - 20 -291.5128173828125 - 30 -0.0 - 10 -438.39007568359375 - 20 -291.45779418945312 - 30 -0.0 - 10 -438.23507690429687 - 20 -291.38531494140625 - 30 -0.0 - 10 -438.08755493164062 - 20 -291.29779052734375 - 30 -0.0 - 10 -437.945068359375 - 20 -291.19281005859375 - 30 -0.0 - 10 -437.81256103515625 - 20 -291.07281494140625 - 30 -0.0 - 10 -437.69256591796875 - 20 -290.9403076171875 - 30 -0.0 - 10 -437.58755493164062 - 20 -290.79779052734375 - 30 -0.0 - 10 -437.50006103515625 - 20 -290.65029907226562 - 30 -0.0 - 10 -437.42758178710937 - 20 -290.49530029296875 - 30 -0.0 - 10 -437.37255859375 - 20 -290.33279418945312 - 30 -0.0 - 10 -437.33258056640625 - 20 -290.17031860351562 - 30 -0.0 - 10 -437.30755615234375 - 20 -290.0028076171875 - 30 -0.0 - 10 -437.30007934570312 - 20 -289.83529663085937 - 30 -0.0 - 10 -437.30755615234375 - 20 -289.66781616210937 - 30 -0.0 - 10 -437.33258056640625 - 20 -289.50030517578125 - 30 -0.0 - 10 -437.37255859375 - 20 -289.33779907226562 - 30 -0.0 - 10 -437.42758178710937 - 20 -289.17529296875 - 30 -0.0 - 10 -437.50006103515625 - 20 -289.02029418945312 - 30 -0.0 - 10 -437.58755493164062 - 20 -288.872802734375 - 30 -0.0 - 10 -437.69256591796875 - 20 -288.73031616210937 - 30 -0.0 - 10 -437.81256103515625 - 20 -288.59780883789062 - 30 -0.0 - 10 -437.945068359375 - 20 -288.47781372070312 - 30 -0.0 - 10 -438.08755493164062 - 20 -288.372802734375 - 30 -0.0 - 10 -438.23507690429687 - 20 -288.28530883789062 - 30 -0.0 - 10 -438.39007568359375 - 20 -288.21279907226563 - 30 -0.0 - 10 -438.55007934570312 - 20 -288.15780639648437 - 30 -0.0 - 10 -438.71505737304687 - 20 -288.1177978515625 - 30 -0.0 - 10 -438.882568359375 - 20 -288.09280395507812 - 30 -0.0 - 10 -439.05007934570312 - 20 -288.08529663085937 - 30 -0.0 - 10 -439.21755981445312 - 20 -288.09280395507812 - 30 -0.0 - 10 -439.382568359375 - 20 -288.1177978515625 - 30 -0.0 - 10 -439.54757690429687 - 20 -288.15780639648437 - 30 -0.0 - 10 -439.70758056640625 - 20 -288.21279907226563 - 30 -0.0 - 10 -439.86257934570312 - 20 -288.28530883789062 - 30 -0.0 - 10 -440.0125732421875 - 20 -288.372802734375 - 30 -0.0 - 10 -440.15505981445312 - 20 -288.47781372070312 - 30 -0.0 - 10 -440.28756713867187 - 20 -288.59780883789062 - 30 -0.0 - 10 -440.28756713867187 - 20 -288.59780883789062 - 30 -0.0 - 0 -LWPOLYLINE - 5 -55 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -66 - 70 -0 - 10 -462.205078125 - 20 -288.59530639648437 - 30 -0.0 - 10 -462.3250732421875 - 20 -288.72781372070312 - 30 -0.0 - 10 -462.4300537109375 - 20 -288.87030029296875 - 30 -0.0 - 10 -462.517578125 - 20 -289.02029418945312 - 30 -0.0 - 10 -462.59005737304687 - 20 -289.17529296875 - 30 -0.0 - 10 -462.64508056640625 - 20 -289.33529663085937 - 30 -0.0 - 10 -462.68505859375 - 20 -289.50030517578125 - 30 -0.0 - 10 -462.71005249023437 - 20 -289.66531372070312 - 30 -0.0 - 10 -462.71755981445312 - 20 -289.83279418945312 - 30 -0.0 - 10 -462.71005249023437 - 20 -290.00030517578125 - 30 -0.0 - 10 -462.68505859375 - 20 -290.16781616210937 - 30 -0.0 - 10 -462.64508056640625 - 20 -290.33279418945312 - 30 -0.0 - 10 -462.59005737304687 - 20 -290.4927978515625 - 30 -0.0 - 10 -462.517578125 - 20 -290.64779663085937 - 30 -0.0 - 10 -462.4300537109375 - 20 -290.79531860351562 - 30 -0.0 - 10 -462.3250732421875 - 20 -290.93780517578125 - 30 -0.0 - 10 -462.205078125 - 20 -291.0703125 - 30 -0.0 - 10 -462.07257080078125 - 20 -291.1903076171875 - 30 -0.0 - 10 -461.9300537109375 - 20 -291.29531860351562 - 30 -0.0 - 10 -461.78256225585937 - 20 -291.3828125 - 30 -0.0 - 10 -461.6275634765625 - 20 -291.45529174804688 - 30 -0.0 - 10 -461.46755981445312 - 20 -291.51031494140625 - 30 -0.0 - 10 -461.30258178710937 - 20 -291.55029296875 - 30 -0.0 - 10 -461.13507080078125 - 20 -291.5753173828125 - 30 -0.0 - 10 -460.96755981445312 - 20 -291.58279418945312 - 30 -0.0 - 10 -460.80007934570312 - 20 -291.5753173828125 - 30 -0.0 - 10 -460.63507080078125 - 20 -291.55029296875 - 30 -0.0 - 10 -460.47006225585938 - 20 -291.51031494140625 - 30 -0.0 - 10 -460.31005859375 - 20 -291.45529174804688 - 30 -0.0 - 10 -460.15505981445312 - 20 -291.3828125 - 30 -0.0 - 10 -460.00506591796875 - 20 -291.29531860351562 - 30 -0.0 - 10 -459.86257934570312 - 20 -291.1903076171875 - 30 -0.0 - 10 -459.73007202148437 - 20 -291.0703125 - 30 -0.0 - 10 -459.61007690429687 - 20 -290.93780517578125 - 30 -0.0 - 10 -459.50506591796875 - 20 -290.79531860351562 - 30 -0.0 - 10 -459.41757202148437 - 20 -290.64779663085937 - 30 -0.0 - 10 -459.34506225585937 - 20 -290.4927978515625 - 30 -0.0 - 10 -459.29006958007813 - 20 -290.33279418945312 - 30 -0.0 - 10 -459.25006103515625 - 20 -290.16781616210937 - 30 -0.0 - 10 -459.22506713867187 - 20 -290.00030517578125 - 30 -0.0 - 10 -459.21755981445312 - 20 -289.83279418945312 - 30 -0.0 - 10 -459.22506713867187 - 20 -289.66531372070312 - 30 -0.0 - 10 -459.25006103515625 - 20 -289.50030517578125 - 30 -0.0 - 10 -459.29006958007813 - 20 -289.33529663085937 - 30 -0.0 - 10 -459.34506225585937 - 20 -289.17529296875 - 30 -0.0 - 10 -459.41757202148437 - 20 -289.02029418945312 - 30 -0.0 - 10 -459.50506591796875 - 20 -288.87030029296875 - 30 -0.0 - 10 -459.61007690429687 - 20 -288.72781372070312 - 30 -0.0 - 10 -459.73007202148437 - 20 -288.59530639648437 - 30 -0.0 - 10 -459.86257934570312 - 20 -288.47531127929687 - 30 -0.0 - 10 -460.00506591796875 - 20 -288.37030029296875 - 30 -0.0 - 10 -460.15505981445312 - 20 -288.28280639648437 - 30 -0.0 - 10 -460.31005859375 - 20 -288.21029663085937 - 30 -0.0 - 10 -460.47006225585938 - 20 -288.15530395507812 - 30 -0.0 - 10 -460.63507080078125 - 20 -288.11529541015625 - 30 -0.0 - 10 -460.80007934570312 - 20 -288.09030151367187 - 30 -0.0 - 10 -460.96755981445312 - 20 -288.08279418945312 - 30 -0.0 - 10 -461.13507080078125 - 20 -288.09030151367187 - 30 -0.0 - 10 -461.30258178710937 - 20 -288.11529541015625 - 30 -0.0 - 10 -461.46755981445312 - 20 -288.15530395507812 - 30 -0.0 - 10 -461.6275634765625 - 20 -288.21029663085937 - 30 -0.0 - 10 -461.78256225585937 - 20 -288.28280639648437 - 30 -0.0 - 10 -461.9300537109375 - 20 -288.37030029296875 - 30 -0.0 - 10 -462.07257080078125 - 20 -288.47531127929687 - 30 -0.0 - 10 -462.205078125 - 20 -288.59530639648437 - 30 -0.0 - 10 -462.205078125 - 20 -288.59530639648437 - 30 -0.0 - 0 -LWPOLYLINE - 5 -56 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -66 - 70 -0 - 10 -451.24505615234375 - 20 -299.55780029296875 - 30 -0.0 - 10 -451.36508178710937 - 20 -299.6903076171875 - 30 -0.0 - 10 -451.47006225585937 - 20 -299.83279418945312 - 30 -0.0 - 10 -451.55755615234375 - 20 -299.98031616210937 - 30 -0.0 - 10 -451.63006591796875 - 20 -300.13531494140625 - 30 -0.0 - 10 -451.68505859375 - 20 -300.29531860351562 - 30 -0.0 - 10 -451.72506713867187 - 20 -300.46029663085937 - 30 -0.0 - 10 -451.75006103515625 - 20 -300.62530517578125 - 30 -0.0 - 10 -451.757568359375 - 20 -300.79531860351562 - 30 -0.0 - 10 -451.75006103515625 - 20 -300.96279907226562 - 30 -0.0 - 10 -451.72506713867187 - 20 -301.1278076171875 - 30 -0.0 - 10 -451.68505859375 - 20 -301.29281616210937 - 30 -0.0 - 10 -451.63006591796875 - 20 -301.45278930664062 - 30 -0.0 - 10 -451.55755615234375 - 20 -301.60781860351562 - 30 -0.0 - 10 -451.47006225585937 - 20 -301.75531005859375 - 30 -0.0 - 10 -451.36508178710937 - 20 -301.89779663085937 - 30 -0.0 - 10 -451.24505615234375 - 20 -302.03030395507812 - 30 -0.0 - 10 -451.11257934570312 - 20 -302.15029907226562 - 30 -0.0 - 10 -450.97006225585937 - 20 -302.25531005859375 - 30 -0.0 - 10 -450.82257080078125 - 20 -302.34280395507812 - 30 -0.0 - 10 -450.66757202148437 - 20 -302.41531372070313 - 30 -0.0 - 10 -450.507568359375 - 20 -302.47030639648437 - 30 -0.0 - 10 -450.34255981445312 - 20 -302.51031494140625 - 30 -0.0 - 10 -450.17507934570312 - 20 -302.53530883789062 - 30 -0.0 - 10 -450.007568359375 - 20 -302.54281616210937 - 30 -0.0 - 10 -449.84005737304687 - 20 -302.53530883789062 - 30 -0.0 - 10 -449.67507934570312 - 20 -302.51031494140625 - 30 -0.0 - 10 -449.51007080078125 - 20 -302.47030639648437 - 30 -0.0 - 10 -449.35006713867187 - 20 -302.41531372070313 - 30 -0.0 - 10 -449.195068359375 - 20 -302.34280395507812 - 30 -0.0 - 10 -449.04507446289062 - 20 -302.25531005859375 - 30 -0.0 - 10 -448.90255737304687 - 20 -302.15029907226562 - 30 -0.0 - 10 -448.77008056640625 - 20 -302.03030395507812 - 30 -0.0 - 10 -448.65005493164062 - 20 -301.89779663085937 - 30 -0.0 - 10 -448.54507446289062 - 20 -301.75531005859375 - 30 -0.0 - 10 -448.45758056640625 - 20 -301.60781860351562 - 30 -0.0 - 10 -448.38507080078125 - 20 -301.45278930664062 - 30 -0.0 - 10 -448.330078125 - 20 -301.29281616210937 - 30 -0.0 - 10 -448.29006958007812 - 20 -301.1278076171875 - 30 -0.0 - 10 -448.26507568359375 - 20 -300.96279907226562 - 30 -0.0 - 10 -448.257568359375 - 20 -300.79531860351562 - 30 -0.0 - 10 -448.26507568359375 - 20 -300.62530517578125 - 30 -0.0 - 10 -448.29006958007812 - 20 -300.46029663085937 - 30 -0.0 - 10 -448.330078125 - 20 -300.29531860351562 - 30 -0.0 - 10 -448.38507080078125 - 20 -300.13531494140625 - 30 -0.0 - 10 -448.45758056640625 - 20 -299.98031616210937 - 30 -0.0 - 10 -448.54507446289062 - 20 -299.83279418945312 - 30 -0.0 - 10 -448.65005493164062 - 20 -299.6903076171875 - 30 -0.0 - 10 -448.77008056640625 - 20 -299.55780029296875 - 30 -0.0 - 10 -448.90255737304687 - 20 -299.43780517578125 - 30 -0.0 - 10 -449.04507446289062 - 20 -299.33279418945312 - 30 -0.0 - 10 -449.195068359375 - 20 -299.24530029296875 - 30 -0.0 - 10 -449.35006713867187 - 20 -299.17279052734375 - 30 -0.0 - 10 -449.51007080078125 - 20 -299.11529541015625 - 30 -0.0 - 10 -449.67507934570312 - 20 -299.0753173828125 - 30 -0.0 - 10 -449.84005737304687 - 20 -299.05279541015625 - 30 -0.0 - 10 -450.007568359375 - 20 -299.04531860351562 - 30 -0.0 - 10 -450.17507934570312 - 20 -299.05279541015625 - 30 -0.0 - 10 -450.34255981445312 - 20 -299.0753173828125 - 30 -0.0 - 10 -450.507568359375 - 20 -299.11529541015625 - 30 -0.0 - 10 -450.66757202148437 - 20 -299.17279052734375 - 30 -0.0 - 10 -450.82257080078125 - 20 -299.24530029296875 - 30 -0.0 - 10 -450.97006225585937 - 20 -299.33279418945312 - 30 -0.0 - 10 -451.11257934570312 - 20 -299.43780517578125 - 30 -0.0 - 10 -451.24505615234375 - 20 -299.55780029296875 - 30 -0.0 - 10 -451.24505615234375 - 20 -299.55780029296875 - 30 -0.0 - 0 -LWPOLYLINE - 5 -57 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -134 - 70 -0 - 10 -400.02005004882812 - 20 -314.72122192382812 - 30 -0.0 - 10 -398.43856811523437 - 20 -311.72457885742187 - 30 -0.0 - 10 -396.94140625 - 20 -308.70230102539062 - 30 -0.0 - 10 -395.52886962890625 - 20 -305.66165161132812 - 30 -0.0 - 10 -394.19638061523437 - 20 -302.6014404296875 - 30 -0.0 - 10 -392.95144653320312 - 20 -299.52108764648437 - 30 -0.0 - 10 -391.788330078125 - 20 -296.424072265625 - 30 -0.0 - 10 -390.70693969726562 - 20 -293.31024169921875 - 30 -0.0 - 10 -389.70614624023437 - 20 -290.18429565429687 - 30 -0.0 - 10 -388.78884887695312 - 20 -287.04437255859375 - 30 -0.0 - 10 -387.95211791992187 - 20 -283.89230346679687 - 30 -0.0 - 10 -387.1976318359375 - 20 -280.73074340820312 - 30 -0.0 - 10 -386.52362060546875 - 20 -277.55709838867187 - 30 -0.0 - 10 -385.92782592773437 - 20 -274.38018798828125 - 30 -0.0 - 10 -385.41598510742187 - 20 -271.1966552734375 - 30 -0.0 - 10 -384.97781372070312 - 20 -268.0089111328125 - 30 -0.0 - 10 -384.62332153320312 - 20 -264.81442260742187 - 30 -0.0 - 10 -384.3460693359375 - 20 -261.62139892578125 - 30 -0.0 - 10 -384.1439208984375 - 20 -258.42678833007812 - 30 -0.0 - 10 -384.02328491210937 - 20 -255.234619140625 - 30 -0.0 - 10 -383.97958374023437 - 20 -252.0438232421875 - 30 -0.0 - 10 -383.9830322265625 - 20 -251.7030029296875 - 30 -0.0 - 10 -384.00137329101562 - 20 -251.69210815429687 - 30 -0.0 - 10 -386.97219848632812 - 20 -250.0264892578125 - 30 -0.0 - 10 -389.96871948242187 - 20 -248.44500732421875 - 30 -0.0 - 10 -392.99099731445312 - 20 -246.94778442382812 - 30 -0.0 - 10 -396.03170776367187 - 20 -245.53518676757813 - 30 -0.0 - 10 -399.09185791015625 - 20 -244.20272827148437 - 30 -0.0 - 10 -402.17221069335938 - 20 -242.95782470703125 - 30 -0.0 - 10 -405.26925659179687 - 20 -241.79470825195312 - 30 -0.0 - 10 -408.38302612304687 - 20 -240.71334838867187 - 30 -0.0 - 10 -411.50900268554687 - 20 -239.71246337890625 - 30 -0.0 - 10 -414.64889526367188 - 20 -238.795166015625 - 30 -0.0 - 10 -417.801025390625 - 20 -237.95846557617187 - 30 -0.0 - 10 -420.96249389648438 - 20 -237.20394897460937 - 30 -0.0 - 10 -424.13623046875 - 20 -236.53005981445312 - 30 -0.0 - 10 -427.31314086914062 - 20 -235.93423461914062 - 30 -0.0 - 10 -430.49484252929687 - 20 -235.41943359375 - 30 -0.0 - 10 -433.6844482421875 - 20 -234.98406982421875 - 30 -0.0 - 10 -436.87722778320312 - 20 -234.62689208984375 - 30 -0.0 - 10 -440.07025146484375 - 20 -234.34942626953125 - 30 -0.0 - 10 -443.2666015625 - 20 -234.1502685546875 - 30 -0.0 - 10 -446.45867919921875 - 20 -234.02957153320312 - 30 -0.0 - 10 -449.64785766601562 - 20 -233.98318481445312 - 30 -0.0 - 10 -452.83453369140625 - 20 -234.01797485351562 - 30 -0.0 - 10 -456.0137939453125 - 20 -234.12582397460938 - 30 -0.0 - 10 -459.18890380859375 - 20 -234.31228637695312 - 30 -0.0 - 10 -462.35537719726562 - 20 -234.57614135742187 - 30 -0.0 - 10 -465.50982666015625 - 20 -234.91152954101562 - 30 -0.0 - 10 -468.65557861328125 - 20 -235.32461547851562 - 30 -0.0 - 10 -471.78829956054687 - 20 -235.81369018554687 - 30 -0.0 - 10 -474.90887451171875 - 20 -236.37451171875 - 30 -0.0 - 10 -478.01193237304687 - 20 -237.01022338867187 - 30 -0.0 - 10 -481.09722900390625 - 20 -237.72100830078125 - 30 -0.0 - 10 -484.16610717773438 - 20 -238.50222778320312 - 30 -0.0 - 10 -487.21435546875 - 20 -239.36007690429687 - 30 -0.0 - 10 -490.243408203125 - 20 -240.29010009765625 - 30 -0.0 - 10 -493.25149536132812 - 20 -241.28933715820312 - 30 -0.0 - 10 -496.23275756835937 - 20 -242.36123657226562 - 30 -0.0 - 10 -499.18740844726562 - 20 -243.50558471679687 - 30 -0.0 - 10 -502.11825561523437 - 20 -244.720947265625 - 30 -0.0 - 10 -505.0206298828125 - 20 -246.00601196289062 - 30 -0.0 - 10 -507.89193725585938 - 20 -247.3623046875 - 30 -0.0 - 10 -510.73477172851562 - 20 -248.78848266601562 - 30 -0.0 - 10 -513.5447998046875 - 20 -250.2830810546875 - 30 -0.0 - 10 -516.0203857421875 - 20 -251.67919921875 - 30 -0.0 - 10 -515.9918212890625 - 20 -254.52120971679687 - 30 -0.0 - 10 -515.881103515625 - 20 -257.70211791992187 - 30 -0.0 - 10 -515.697509765625 - 20 -260.8756103515625 - 30 -0.0 - 10 -515.4337158203125 - 20 -264.0419921875 - 30 -0.0 - 10 -515.09527587890625 - 20 -267.19818115234375 - 30 -0.0 - 10 -514.682373046875 - 20 -270.34396362304688 - 30 -0.0 - 10 -514.19775390625 - 20 -273.47781372070313 - 30 -0.0 - 10 -513.6353759765625 - 20 -276.5955810546875 - 30 -0.0 - 10 -512.99957275390625 - 20 -279.69857788085937 - 30 -0.0 - 10 -512.288818359375 - 20 -282.783935546875 - 30 -0.0 - 10 -511.5047607421875 - 20 -285.85443115234375 - 30 -0.0 - 10 -510.6485595703125 - 20 -288.9056396484375 - 30 -0.0 - 10 -509.72134399414062 - 20 -291.9329833984375 - 30 -0.0 - 10 -508.72048950195312 - 20 -294.9381103515625 - 30 -0.0 - 10 -507.64862060546875 - 20 -297.91940307617187 - 30 -0.0 - 10 -506.50137329101562 - 20 -300.87576293945312 - 30 -0.0 - 10 -505.28607177734375 - 20 -303.8065185546875 - 30 -0.0 - 10 -504.0010986328125 - 20 -306.70895385742187 - 30 -0.0 - 10 -502.64633178710937 - 20 -309.5831298828125 - 30 -0.0 - 10 -501.21865844726562 - 20 -312.42315673828125 - 30 -0.0 - 10 -499.72402954101562 - 20 -315.23324584960937 - 30 -0.0 - 10 -498.15927124023437 - 20 -318.00765991210937 - 30 -0.0 - 10 -496.52593994140625 - 20 -320.74917602539062 - 30 -0.0 - 10 -494.82540893554687 - 20 -323.45327758789062 - 30 -0.0 - 10 -493.05307006835937 - 20 -326.11883544921875 - 30 -0.0 - 10 -491.21633911132812 - 20 -328.74545288085937 - 30 -0.0 - 10 -489.31503295898438 - 20 -331.33303833007812 - 30 -0.0 - 10 -487.34158325195312 - 20 -333.87469482421875 - 30 -0.0 - 10 -485.30361938476562 - 20 -336.37728881835937 - 30 -0.0 - 10 -483.19924926757812 - 20 -338.83071899414062 - 30 -0.0 - 10 -481.03155517578125 - 20 -341.24053955078125 - 30 -0.0 - 10 -478.79449462890625 - 20 -343.60287475585937 - 30 -0.0 - 10 -476.49380493164062 - 20 -345.914306640625 - 30 -0.0 - 10 -474.12942504882812 - 20 -348.17486572265625 - 30 -0.0 - 10 -471.69967651367187 - 20 -350.38165283203125 - 30 -0.0 - 10 -469.2091064453125 - 20 -352.535888671875 - 30 -0.0 - 10 -466.65325927734375 - 20 -354.63641357421875 - 30 -0.0 - 10 -464.03207397460938 - 20 -356.68325805664062 - 30 -0.0 - 10 -461.35089111328125 - 20 -358.66558837890625 - 30 -0.0 - 10 -458.607177734375 - 20 -360.59259033203125 - 30 -0.0 - 10 -455.79946899414062 - 20 -362.46136474609375 - 30 -0.0 - 10 -452.93161010742187 - 20 -364.26568603515625 - 30 -0.0 - 10 -450.00369262695312 - 20 -366.00567626953125 - 30 -0.0 - 10 -449.98391723632812 - 20 -366.01678466796875 - 30 -0.0 - 10 -449.6837158203125 - 20 -365.84738159179687 - 30 -0.0 - 10 -446.9422607421875 - 20 -364.21417236328125 - 30 -0.0 - 10 -444.23806762695312 - 20 -362.51361083984375 - 30 -0.0 - 10 -441.572509765625 - 20 -360.74127197265625 - 30 -0.0 - 10 -438.9459228515625 - 20 -358.90447998046875 - 30 -0.0 - 10 -436.35836791992187 - 20 -357.0032958984375 - 30 -0.0 - 10 -433.81668090820312 - 20 -355.02978515625 - 30 -0.0 - 10 -431.31405639648437 - 20 -352.99188232421875 - 30 -0.0 - 10 -428.86068725585938 - 20 -350.887451171875 - 30 -0.0 - 10 -426.45071411132812 - 20 -348.71978759765625 - 30 -0.0 - 10 -424.0885009765625 - 20 -346.48272705078125 - 30 -0.0 - 10 -421.77700805664062 - 20 -344.18206787109375 - 30 -0.0 - 10 -419.5164794921875 - 20 -341.817626953125 - 30 -0.0 - 10 -417.30960083007812 - 20 -339.387939453125 - 30 -0.0 - 10 -415.15548706054687 - 20 -336.89743041992187 - 30 -0.0 - 10 -413.05490112304687 - 20 -334.34158325195312 - 30 -0.0 - 10 -411.008056640625 - 20 -331.7203369140625 - 30 -0.0 - 10 -409.02569580078125 - 20 -329.03915405273437 - 30 -0.0 - 10 -407.09869384765625 - 20 -326.29547119140625 - 30 -0.0 - 10 -405.22998046875 - 20 -323.4876708984375 - 30 -0.0 - 10 -403.4256591796875 - 20 -320.61990356445312 - 30 -0.0 - 10 -401.6856689453125 - 20 -317.69192504882812 - 30 -0.0 - 10 -400.02005004882812 - 20 -314.72122192382812 - 30 -0.0 - 10 -400.02005004882812 - 20 -314.72122192382812 - 30 -0.0 - 0 -LWPOLYLINE - 5 -58 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -50 - 70 -0 - 10 -448.257568359375 - 20 -359.26278686523437 - 30 -0.0 - 10 -448.267578125 - 20 -359.08279418945312 - 30 -0.0 - 10 -448.29257202148437 - 20 -358.9102783203125 - 30 -0.0 - 10 -448.33755493164063 - 20 -358.7427978515625 - 30 -0.0 - 10 -448.39508056640625 - 20 -358.58029174804688 - 30 -0.0 - 10 -448.55755615234375 - 20 -358.28277587890625 - 30 -0.0 - 10 -448.77008056640625 - 20 -358.02529907226562 - 30 -0.0 - 10 -449.03005981445312 - 20 -357.810302734375 - 30 -0.0 - 10 -449.32757568359375 - 20 -357.65029907226562 - 30 -0.0 - 10 -449.48757934570312 - 20 -357.59030151367187 - 30 -0.0 - 10 -449.65505981445312 - 20 -357.54779052734375 - 30 -0.0 - 10 -449.830078125 - 20 -357.52279663085937 - 30 -0.0 - 10 -450.007568359375 - 20 -357.51278686523437 - 30 -0.0 - 10 -450.18756103515625 - 20 -357.52279663085937 - 30 -0.0 - 10 -450.36007690429687 - 20 -357.54779052734375 - 30 -0.0 - 10 -450.52755737304687 - 20 -357.59030151367187 - 30 -0.0 - 10 -450.6900634765625 - 20 -357.65029907226562 - 30 -0.0 - 10 -450.98757934570312 - 20 -357.810302734375 - 30 -0.0 - 10 -451.24505615234375 - 20 -358.02529907226562 - 30 -0.0 - 10 -451.46005249023437 - 20 -358.28277587890625 - 30 -0.0 - 10 -451.62005615234375 - 20 -358.58029174804688 - 30 -0.0 - 10 -451.6800537109375 - 20 -358.7427978515625 - 30 -0.0 - 10 -451.72256469726562 - 20 -358.9102783203125 - 30 -0.0 - 10 -451.74755859375 - 20 -359.08279418945312 - 30 -0.0 - 10 -451.757568359375 - 20 -359.26278686523437 - 30 -0.0 - 10 -451.74755859375 - 20 -359.44027709960937 - 30 -0.0 - 10 -451.72256469726562 - 20 -359.61529541015625 - 30 -0.0 - 10 -451.6800537109375 - 20 -359.78277587890625 - 30 -0.0 - 10 -451.62005615234375 - 20 -359.94277954101562 - 30 -0.0 - 10 -451.46005249023437 - 20 -360.24029541015625 - 30 -0.0 - 10 -451.24505615234375 - 20 -360.49777221679687 - 30 -0.0 - 10 -450.98757934570312 - 20 -360.71279907226562 - 30 -0.0 - 10 -450.6900634765625 - 20 -360.87277221679687 - 30 -0.0 - 10 -450.52755737304687 - 20 -360.93280029296875 - 30 -0.0 - 10 -450.36007690429687 - 20 -360.97528076171875 - 30 -0.0 - 10 -450.18756103515625 - 20 -361.00027465820312 - 30 -0.0 - 10 -450.007568359375 - 20 -361.01028442382812 - 30 -0.0 - 10 -449.830078125 - 20 -361.00027465820312 - 30 -0.0 - 10 -449.65505981445312 - 20 -360.97528076171875 - 30 -0.0 - 10 -449.48757934570312 - 20 -360.93280029296875 - 30 -0.0 - 10 -449.32757568359375 - 20 -360.87277221679687 - 30 -0.0 - 10 -449.03005981445312 - 20 -360.71279907226562 - 30 -0.0 - 10 -448.77008056640625 - 20 -360.49777221679687 - 30 -0.0 - 10 -448.55755615234375 - 20 -360.24029541015625 - 30 -0.0 - 10 -448.39508056640625 - 20 -359.94277954101562 - 30 -0.0 - 10 -448.33755493164063 - 20 -359.78277587890625 - 30 -0.0 - 10 -448.29257202148437 - 20 -359.61529541015625 - 30 -0.0 - 10 -448.267578125 - 20 -359.44027709960937 - 30 -0.0 - 10 -448.257568359375 - 20 -359.26278686523437 - 30 -0.0 - 10 -448.257568359375 - 20 -359.26278686523437 - 30 -0.0 - 0 -LWPOLYLINE - 5 -59 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -54 - 70 -0 - 10 -390.64007568359375 - 20 -253.68777465820312 - 30 -0.0 - 10 -390.92758178710937 - 20 -253.895263671875 - 30 -0.0 - 10 -391.16256713867187 - 20 -254.14776611328125 - 30 -0.0 - 10 -391.33755493164063 - 20 -254.43527221679687 - 30 -0.0 - 10 -391.40505981445312 - 20 -254.59027099609375 - 30 -0.0 - 10 -391.455078125 - 20 -254.75027465820313 - 30 -0.0 - 10 -391.4925537109375 - 20 -254.915283203125 - 30 -0.0 - 10 -391.5125732421875 - 20 -255.08026123046875 - 30 -0.0 - 10 -391.51507568359375 - 20 -255.25027465820312 - 30 -0.0 - 10 -391.5025634765625 - 20 -255.4202880859375 - 30 -0.0 - 10 -391.47256469726562 - 20 -255.5877685546875 - 30 -0.0 - 10 -391.42507934570312 - 20 -255.75527954101562 - 30 -0.0 - 10 -391.36257934570312 - 20 -255.9202880859375 - 30 -0.0 - 10 -391.28005981445312 - 20 -256.08026123046875 - 30 -0.0 - 10 -391.07257080078125 - 20 -256.36776733398438 - 30 -0.0 - 10 -390.820068359375 - 20 -256.60028076171875 - 30 -0.0 - 10 -390.53256225585937 - 20 -256.77777099609375 - 30 -0.0 - 10 -390.3775634765625 - 20 -256.84527587890625 - 30 -0.0 - 10 -390.21755981445312 - 20 -256.895263671875 - 30 -0.0 - 10 -390.05258178710937 - 20 -256.93026733398437 - 30 -0.0 - 10 -389.88507080078125 - 20 -256.95028686523437 - 30 -0.0 - 10 -389.71755981445312 - 20 -256.95526123046875 - 30 -0.0 - 10 -389.54757690429687 - 20 -256.94277954101562 - 30 -0.0 - 10 -389.3775634765625 - 20 -256.91278076171875 - 30 -0.0 - 10 -389.2100830078125 - 20 -256.86526489257812 - 30 -0.0 - 10 -389.04757690429687 - 20 -256.80276489257812 - 30 -0.0 - 10 -388.8875732421875 - 20 -256.72027587890625 - 30 -0.0 - 10 -388.60006713867187 - 20 -256.51278686523437 - 30 -0.0 - 10 -388.36508178710937 - 20 -256.26028442382812 - 30 -0.0 - 10 -388.1900634765625 - 20 -255.97027587890625 - 30 -0.0 - 10 -388.12255859375 - 20 -255.81527709960937 - 30 -0.0 - 10 -388.07257080078125 - 20 -255.6552734375 - 30 -0.0 - 10 -388.03506469726562 - 20 -255.49276733398438 - 30 -0.0 - 10 -388.01507568359375 - 20 -255.32528686523437 - 30 -0.0 - 10 -388.0125732421875 - 20 -255.1552734375 - 30 -0.0 - 10 -388.02505493164062 - 20 -254.98776245117187 - 30 -0.0 - 10 -388.0550537109375 - 20 -254.81777954101562 - 30 -0.0 - 10 -388.10256958007812 - 20 -254.6502685546875 - 30 -0.0 - 10 -388.16506958007812 - 20 -254.48776245117187 - 30 -0.0 - 10 -388.24755859375 - 20 -254.32778930664062 - 30 -0.0 - 10 -388.455078125 - 20 -254.040283203125 - 30 -0.0 - 10 -388.70758056640625 - 20 -253.80526733398437 - 30 -0.0 - 10 -388.99505615234375 - 20 -253.63027954101562 - 30 -0.0 - 10 -389.15005493164062 - 20 -253.56277465820313 - 30 -0.0 - 10 -389.31005859375 - 20 -253.51278686523437 - 30 -0.0 - 10 -389.47506713867187 - 20 -253.47528076171875 - 30 -0.0 - 10 -389.642578125 - 20 -253.45526123046875 - 30 -0.0 - 10 -389.81005859375 - 20 -253.45278930664062 - 30 -0.0 - 10 -389.98007202148437 - 20 -253.46527099609375 - 30 -0.0 - 10 -390.15005493164062 - 20 -253.49526977539062 - 30 -0.0 - 10 -390.31756591796875 - 20 -253.54278564453125 - 30 -0.0 - 10 -390.48007202148437 - 20 -253.60528564453125 - 30 -0.0 - 10 -390.64007568359375 - 20 -253.68777465820312 - 30 -0.0 - 10 -390.64007568359375 - 20 -253.68777465820312 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5A -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -54 - 70 -0 - 10 -511.03256225585937 - 20 -256.58529663085937 - 30 -0.0 - 10 -510.87255859375 - 20 -256.66781616210937 - 30 -0.0 - 10 -510.71005249023437 - 20 -256.73031616210937 - 30 -0.0 - 10 -510.54254150390625 - 20 -256.77780151367187 - 30 -0.0 - 10 -510.37255859375 - 20 -256.8052978515625 - 30 -0.0 - 10 -510.20504760742187 - 20 -256.81781005859375 - 30 -0.0 - 10 -510.03506469726562 - 20 -256.8153076171875 - 30 -0.0 - 10 -509.8675537109375 - 20 -256.79531860351562 - 30 -0.0 - 10 -509.70504760742187 - 20 -256.76031494140625 - 30 -0.0 - 10 -509.5450439453125 - 20 -256.70779418945312 - 30 -0.0 - 10 -509.39004516601562 - 20 -256.64031982421875 - 30 -0.0 - 10 -509.1025390625 - 20 -256.46530151367187 - 30 -0.0 - 10 -508.85003662109375 - 20 -256.23031616210937 - 30 -0.0 - 10 -508.64254760742187 - 20 -255.94281005859375 - 30 -0.0 - 10 -508.56005859375 - 20 -255.78280639648438 - 30 -0.0 - 10 -508.49755859375 - 20 -255.62030029296875 - 30 -0.0 - 10 -508.45004272460937 - 20 -255.45281982421875 - 30 -0.0 - 10 -508.4200439453125 - 20 -255.28530883789063 - 30 -0.0 - 10 -508.40756225585938 - 20 -255.11529541015625 - 30 -0.0 - 10 -508.41253662109375 - 20 -254.94781494140625 - 30 -0.0 - 10 -508.43255615234375 - 20 -254.78030395507812 - 30 -0.0 - 10 -508.46755981445312 - 20 -254.61529541015625 - 30 -0.0 - 10 -508.51754760742188 - 20 -254.45529174804687 - 30 -0.0 - 10 -508.58505249023437 - 20 -254.30029296875 - 30 -0.0 - 10 -508.76254272460937 - 20 -254.0128173828125 - 30 -0.0 - 10 -508.99505615234375 - 20 -253.76031494140625 - 30 -0.0 - 10 -509.28256225585937 - 20 -253.55279541015625 - 30 -0.0 - 10 -509.44256591796875 - 20 -253.47030639648437 - 30 -0.0 - 10 -509.60504150390625 - 20 -253.40780639648437 - 30 -0.0 - 10 -509.77255249023437 - 20 -253.36029052734375 - 30 -0.0 - 10 -509.94256591796875 - 20 -253.33279418945313 - 30 -0.0 - 10 -510.11004638671875 - 20 -253.3203125 - 30 -0.0 - 10 -510.28005981445312 - 20 -253.32281494140625 - 30 -0.0 - 10 -510.44754028320312 - 20 -253.34280395507812 - 30 -0.0 - 10 -510.61004638671875 - 20 -253.3778076171875 - 30 -0.0 - 10 -510.77005004882812 - 20 -253.4302978515625 - 30 -0.0 - 10 -510.925048828125 - 20 -253.49530029296875 - 30 -0.0 - 10 -511.21255493164063 - 20 -253.67279052734375 - 30 -0.0 - 10 -511.46505737304687 - 20 -253.90530395507812 - 30 -0.0 - 10 -511.67254638671875 - 20 -254.19281005859375 - 30 -0.0 - 10 -511.75506591796875 - 20 -254.35281372070312 - 30 -0.0 - 10 -511.81756591796875 - 20 -254.51531982421875 - 30 -0.0 - 10 -511.86505126953125 - 20 -254.68280029296875 - 30 -0.0 - 10 -511.89505004882812 - 20 -254.85281372070313 - 30 -0.0 - 10 -511.90756225585937 - 20 -255.02029418945312 - 30 -0.0 - 10 -511.90505981445312 - 20 -255.1903076171875 - 30 -0.0 - 10 -511.88504028320312 - 20 -255.35781860351562 - 30 -0.0 - 10 -511.84756469726562 - 20 -255.52029418945312 - 30 -0.0 - 10 -511.79754638671875 - 20 -255.6802978515625 - 30 -0.0 - 10 -511.73004150390625 - 20 -255.83529663085937 - 30 -0.0 - 10 -511.5550537109375 - 20 -256.12530517578125 - 30 -0.0 - 10 -511.32003784179687 - 20 -256.3778076171875 - 30 -0.0 - 10 -511.03256225585937 - 20 -256.58529663085937 - 30 -0.0 - 10 -511.03256225585937 - 20 -256.58529663085937 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5B -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -80 - 70 -0 - 10 -452.38726806640625 - 20 -242.75088500976562 - 30 -0.0 - 10 -455.05783081054687 - 20 -242.8414306640625 - 30 -0.0 - 10 -457.72494506835937 - 20 -242.998046875 - 30 -0.0 - 10 -460.38470458984375 - 20 -243.21975708007812 - 30 -0.0 - 10 -463.03445434570312 - 20 -243.50152587890625 - 30 -0.0 - 10 -465.677001953125 - 20 -243.848388671875 - 30 -0.0 - 10 -468.308349609375 - 20 -244.25927734375 - 30 -0.0 - 10 -470.92971801757812 - 20 -244.7303466796875 - 30 -0.0 - 10 -473.53622436523437 - 20 -245.264404296875 - 30 -0.0 - 10 -476.12783813476562 - 20 -245.8614501953125 - 30 -0.0 - 10 -478.70578002929687 - 20 -246.517578125 - 30 -0.0 - 10 -481.266357421875 - 20 -247.23822021484375 - 30 -0.0 - 10 -483.81072998046875 - 20 -248.0194091796875 - 30 -0.0 - 10 -486.33746337890625 - 20 -248.85879516601562 - 30 -0.0 - 10 -488.84176635742187 - 20 -249.7591552734375 - 30 -0.0 - 10 -491.32363891601562 - 20 -250.720458984375 - 30 -0.0 - 10 -493.78558349609375 - 20 -251.74136352539062 - 30 -0.0 - 10 -496.22360229492187 - 20 -252.82077026367188 - 30 -0.0 - 10 -498.63546752929687 - 20 -253.9600830078125 - 30 -0.0 - 10 -499.23004150390625 - 20 -254.25836181640625 - 30 -0.0 - 10 -484.1573486328125 - 20 -262.9605712890625 - 30 -0.0 - 10 -483.8927001953125 - 20 -262.83554077148437 - 30 -0.0 - 10 -482.10479736328125 - 20 -262.04397583007812 - 30 -0.0 - 10 -480.29937744140625 - 20 -261.29534912109375 - 30 -0.0 - 10 -478.47940063476562 - 20 -260.59033203125 - 30 -0.0 - 10 -476.642822265625 - 20 -259.93014526367187 - 30 -0.0 - 10 -474.7899169921875 - 20 -259.3145751953125 - 30 -0.0 - 10 -472.924072265625 - 20 -258.74172973632812 - 30 -0.0 - 10 -471.04632568359375 - 20 -258.2132568359375 - 30 -0.0 - 10 -469.15576171875 - 20 -257.73208618164062 - 30 -0.0 - 10 -467.25531005859375 - 20 -257.29425048828125 - 30 -0.0 - 10 -465.34384155273437 - 20 -256.90261840820312 - 30 -0.0 - 10 -463.42156982421875 - 20 -256.55712890625 - 30 -0.0 - 10 -461.49185180664062 - 20 -256.255859375 - 30 -0.0 - 10 -459.55401611328125 - 20 -256.00140380859375 - 30 -0.0 - 10 -457.61083984375 - 20 -255.79483032226562 - 30 -0.0 - 10 -455.66030883789062 - 20 -255.63229370117187 - 30 -0.0 - 10 -453.70452880859375 - 20 -255.51748657226563 - 30 -0.0 - 10 -451.74603271484375 - 20 -255.45098876953125 - 30 -0.0 - 10 -449.7830810546875 - 20 -255.42953491210937 - 30 -0.0 - 10 -447.8184814453125 - 20 -255.45819091796875 - 30 -0.0 - 10 -445.8521728515625 - 20 -255.53253173828125 - 30 -0.0 - 10 -443.88320922851562 - 20 -255.65518188476562 - 30 -0.0 - 10 -441.91635131835937 - 20 -255.82601928710938 - 30 -0.0 - 10 -439.94961547851562 - 20 -256.046142578125 - 30 -0.0 - 10 -437.98483276367187 - 20 -256.3143310546875 - 30 -0.0 - 10 -436.02487182617187 - 20 -256.63137817382812 - 30 -0.0 - 10 -434.06790161132812 - 20 -256.99838256835937 - 30 -0.0 - 10 -432.11288452148437 - 20 -257.41342163085937 - 30 -0.0 - 10 -430.16543579101562 - 20 -257.8782958984375 - 30 -0.0 - 10 -428.22369384765625 - 20 -258.3936767578125 - 30 -0.0 - 10 -426.28952026367188 - 20 -258.95883178710937 - 30 -0.0 - 10 -424.36386108398437 - 20 -259.5753173828125 - 30 -0.0 - 10 -422.44583129882812 - 20 -260.24139404296875 - 30 -0.0 - 10 -420.53799438476562 - 20 -260.95791625976562 - 30 -0.0 - 10 -418.64056396484375 - 20 -261.72476196289062 - 30 -0.0 - 10 -416.7554931640625 - 20 -262.54559326171875 - 30 -0.0 - 10 -415.56683349609375 - 20 -263.09774780273437 - 30 -0.0 - 10 -400.51385498046875 - 20 -254.40689086914063 - 30 -0.0 - 10 -402.11865234375 - 20 -253.6119384765625 - 30 -0.0 - 10 -404.67279052734375 - 20 -252.4254150390625 - 30 -0.0 - 10 -407.24346923828125 - 20 -251.30609130859375 - 30 -0.0 - 10 -409.83087158203125 - 20 -250.26031494140625 - 30 -0.0 - 10 -412.432373046875 - 20 -249.28323364257812 - 30 -0.0 - 10 -415.04800415039063 - 20 -248.37493896484375 - 30 -0.0 - 10 -417.673828125 - 20 -247.53427124023437 - 30 -0.0 - 10 -420.31137084960937 - 20 -246.763671875 - 30 -0.0 - 10 -422.95913696289062 - 20 -246.06088256835937 - 30 -0.0 - 10 -425.61471557617187 - 20 -245.42709350585937 - 30 -0.0 - 10 -428.28070068359375 - 20 -244.86099243164062 - 30 -0.0 - 10 -430.94931030273437 - 20 -244.36056518554687 - 30 -0.0 - 10 -433.62200927734375 - 20 -243.9281005859375 - 30 -0.0 - 10 -436.30120849609375 - 20 -243.56240844726562 - 30 -0.0 - 10 -438.98309326171875 - 20 -243.26239013671875 - 30 -0.0 - 10 -441.665283203125 - 20 -243.02938842773437 - 30 -0.0 - 10 -444.35006713867187 - 20 -242.86203002929687 - 30 -0.0 - 10 -447.031494140625 - 20 -242.76065063476562 - 30 -0.0 - 10 -449.71044921875 - 20 -242.72149658203125 - 30 -0.0 - 10 -452.38726806640625 - 20 -242.75088500976562 - 30 -0.0 - 10 -452.38726806640625 - 20 -242.75088500976562 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5C -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -78 - 70 -0 - 10 -409.65127563476562 - 20 -273.53872680664062 - 30 -0.0 - 10 -409.72793579101562 - 20 -274.42153930664062 - 30 -0.0 - 10 -409.94638061523437 - 20 -276.38934326171875 - 30 -0.0 - 10 -410.2161865234375 - 20 -278.35299682617188 - 30 -0.0 - 10 -410.53158569335938 - 20 -280.31405639648437 - 30 -0.0 - 10 -410.89859008789063 - 20 -282.27099609375 - 30 -0.0 - 10 -411.31369018554687 - 20 -284.22598266601562 - 30 -0.0 - 10 -411.77850341796875 - 20 -286.1734619140625 - 30 -0.0 - 10 -412.29391479492187 - 20 -288.11514282226562 - 30 -0.0 - 10 -412.85903930664062 - 20 -290.04934692382812 - 30 -0.0 - 10 -413.47549438476562 - 20 -291.97491455078125 - 30 -0.0 - 10 -414.14151000976562 - 20 -293.89306640625 - 30 -0.0 - 10 -414.8580322265625 - 20 -295.80081176757812 - 30 -0.0 - 10 -415.62496948242187 - 20 -297.69830322265625 - 30 -0.0 - 10 -416.44570922851562 - 20 -299.58340454101562 - 30 -0.0 - 10 -417.31585693359375 - 20 -301.45648193359375 - 30 -0.0 - 10 -418.23806762695312 - 20 -303.31820678710937 - 30 -0.0 - 10 -419.21234130859375 - 20 -305.16412353515625 - 30 -0.0 - 10 -420.23837280273437 - 20 -306.99407958984375 - 30 -0.0 - 10 -421.31024169921875 - 20 -308.7977294921875 - 30 -0.0 - 10 -422.42166137695312 - 20 -310.56423950195312 - 30 -0.0 - 10 -423.57278442382812 - 20 -312.29385375976562 - 30 -0.0 - 10 -424.759765625 - 20 -313.98394775390625 - 30 -0.0 - 10 -425.98095703125 - 20 -315.63555908203125 - 30 -0.0 - 10 -427.24179077148437 - 20 -317.25021362304688 - 30 -0.0 - 10 -428.5357666015625 - 20 -318.82464599609375 - 30 -0.0 - 10 -429.86273193359375 - 20 -320.35873413085937 - 30 -0.0 - 10 -431.22216796875 - 20 -321.85546875 - 30 -0.0 - 10 -432.6146240234375 - 20 -323.31198120117187 - 30 -0.0 - 10 -434.03851318359375 - 20 -324.72921752929687 - 30 -0.0 - 10 -435.49362182617187 - 20 -326.10733032226562 - 30 -0.0 - 10 -436.97808837890625 - 20 -327.44253540039062 - 30 -0.0 - 10 -438.48941040039062 - 20 -328.73886108398437 - 30 -0.0 - 10 -440.031005859375 - 20 -329.99417114257812 - 30 -0.0 - 10 -441.59661865234375 - 20 -331.20986938476562 - 30 -0.0 - 10 -443.19064331054687 - 20 -332.3809814453125 - 30 -0.0 - 10 -443.50909423828125 - 20 -332.60366821289062 - 30 -0.0 - 10 -443.50906372070313 - 20 -349.5853271484375 - 30 -0.0 - 10 -442.92715454101562 - 20 -349.19839477539062 - 30 -0.0 - 10 -440.72079467773437 - 20 -347.6553955078125 - 30 -0.0 - 10 -438.54721069335937 - 20 -346.0584716796875 - 30 -0.0 - 10 -436.4122314453125 - 20 -344.40066528320313 - 30 -0.0 - 10 -434.31002807617187 - 20 -342.68887329101562 - 30 -0.0 - 10 -432.24917602539062 - 20 -340.92117309570312 - 30 -0.0 - 10 -430.224853515625 - 20 -339.10043334960937 - 30 -0.0 - 10 -428.24053955078125 - 20 -337.22125244140625 - 30 -0.0 - 10 -426.2989501953125 - 20 -335.28866577148437 - 30 -0.0 - 10 -424.40008544921875 - 20 -333.30245971679687 - 30 -0.0 - 10 -422.54635620117187 - 20 -331.26150512695312 - 30 -0.0 - 10 -420.73681640625 - 20 -329.1695556640625 - 30 -0.0 - 10 -418.97232055664062 - 20 -327.02264404296875 - 30 -0.0 - 10 -417.25299072265625 - 20 -324.82086181640625 - 30 -0.0 - 10 -415.58782958984375 - 20 -322.568603515625 - 30 -0.0 - 10 -413.9691162109375 - 20 -320.26388549804687 - 30 -0.0 - 10 -412.3994140625 - 20 -317.90536499023437 - 30 -0.0 - 10 -410.88375854492187 - 20 -315.496337890625 - 30 -0.0 - 10 -409.42221069335937 - 20 -313.03701782226562 - 30 -0.0 - 10 -408.0230712890625 - 20 -310.54147338867187 - 30 -0.0 - 10 -406.69464111328125 - 20 -308.02438354492187 - 30 -0.0 - 10 -405.43707275390625 - 20 -305.48565673828125 - 30 -0.0 - 10 -404.25048828125 - 20 -302.93148803710938 - 30 -0.0 - 10 -403.13116455078125 - 20 -300.36090087890625 - 30 -0.0 - 10 -402.08547973632812 - 20 -297.77337646484375 - 30 -0.0 - 10 -401.10842895507812 - 20 -295.17193603515625 - 30 -0.0 - 10 -400.2000732421875 - 20 -292.55630493164062 - 30 -0.0 - 10 -399.35943603515625 - 20 -289.93045043945312 - 30 -0.0 - 10 -398.58880615234375 - 20 -287.29296875 - 30 -0.0 - 10 -397.88595581054687 - 20 -284.64517211914062 - 30 -0.0 - 10 -397.252197265625 - 20 -281.98956298828125 - 30 -0.0 - 10 -396.68612670898437 - 20 -279.32357788085938 - 30 -0.0 - 10 -396.1856689453125 - 20 -276.655029296875 - 30 -0.0 - 10 -395.75564575195312 - 20 -273.98095703125 - 30 -0.0 - 10 -395.38766479492187 - 20 -271.30322265625 - 30 -0.0 - 10 -395.08987426757812 - 20 -268.619873046875 - 30 -0.0 - 10 -394.85690307617187 - 20 -265.93771362304687 - 30 -0.0 - 10 -394.79513549804687 - 20 -264.96151733398437 - 30 -0.0 - 10 -409.65127563476562 - 20 -273.53872680664062 - 30 -0.0 - 10 -409.65127563476562 - 20 -273.53872680664062 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5D -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -80 - 70 -0 - 10 -505.19219970703125 - 20 -265.31121826171875 - 30 -0.0 - 10 -504.9705810546875 - 20 -267.97097778320312 - 30 -0.0 - 10 -504.68637084960937 - 20 -270.62210083007812 - 30 -0.0 - 10 -504.33950805664062 - 20 -273.26461791992187 - 30 -0.0 - 10 -503.93246459960937 - 20 -275.89703369140625 - 30 -0.0 - 10 -503.46002197265625 - 20 -278.5159912109375 - 30 -0.0 - 10 -502.9259033203125 - 20 -281.12249755859375 - 30 -0.0 - 10 -502.328857421875 - 20 -283.71417236328125 - 30 -0.0 - 10 -501.67031860351562 - 20 -286.29336547851562 - 30 -0.0 - 10 -500.9510498046875 - 20 -288.8564453125 - 30 -0.0 - 10 -500.17218017578125 - 20 -291.39932250976563 - 30 -0.0 - 10 -499.3314208984375 - 20 -293.9237060546875 - 30 -0.0 - 10 -498.43118286132812 - 20 -296.42800903320312 - 30 -0.0 - 10 -497.4674072265625 - 20 -298.91131591796875 - 30 -0.0 - 10 -496.44656372070312 - 20 -301.37319946289062 - 30 -0.0 - 10 -495.36715698242187 - 20 -303.811279296875 - 30 -0.0 - 10 -494.22915649414062 - 20 -306.22555541992187 - 30 -0.0 - 10 -493.0299072265625 - 20 -308.6112060546875 - 30 -0.0 - 10 -491.7744140625 - 20 -310.97161865234375 - 30 -0.0 - 10 -490.45999145507812 - 20 -313.3021240234375 - 30 -0.0 - 10 -489.08804321289062 - 20 -315.60501098632812 - 30 -0.0 - 10 -487.65960693359375 - 20 -317.87649536132812 - 30 -0.0 - 10 -486.17083740234375 - 20 -320.11563110351562 - 30 -0.0 - 10 -484.62789916992187 - 20 -322.3218994140625 - 30 -0.0 - 10 -483.0308837890625 - 20 -324.49551391601562 - 30 -0.0 - 10 -481.37313842773437 - 20 -326.63037109375 - 30 -0.0 - 10 -479.661376953125 - 20 -328.73257446289062 - 30 -0.0 - 10 -477.8935546875 - 20 -330.79345703125 - 30 -0.0 - 10 -476.07272338867187 - 20 -332.81771850585937 - 30 -0.0 - 10 -474.19363403320312 - 20 -334.80209350585937 - 30 -0.0 - 10 -472.26104736328125 - 20 -336.74368286132812 - 30 -0.0 - 10 -470.27490234375 - 20 -338.642578125 - 30 -0.0 - 10 -468.23394775390625 - 20 -340.49627685546875 - 30 -0.0 - 10 -466.14190673828125 - 20 -342.30584716796875 - 30 -0.0 - 10 -463.99496459960937 - 20 -344.07034301757812 - 30 -0.0 - 10 -461.793212890625 - 20 -345.78961181640625 - 30 -0.0 - 10 -459.54098510742188 - 20 -347.45486450195312 - 30 -0.0 - 10 -457.23626708984375 - 20 -349.073486328125 - 30 -0.0 - 10 -455.50909423828125 - 20 -350.22311401367187 - 30 -0.0 - 10 -455.50912475585937 - 20 -333.27545166015625 - 30 -0.0 - 10 -456.99209594726562 - 20 -332.23385620117187 - 30 -0.0 - 10 -458.64373779296875 - 20 -331.01275634765625 - 30 -0.0 - 10 -460.25833129882812 - 20 -329.751953125 - 30 -0.0 - 10 -461.83282470703125 - 20 -328.45791625976562 - 30 -0.0 - 10 -463.36700439453125 - 20 -327.13095092773437 - 30 -0.0 - 10 -464.86370849609375 - 20 -325.77163696289062 - 30 -0.0 - 10 -466.32022094726562 - 20 -324.37905883789062 - 30 -0.0 - 10 -467.7374267578125 - 20 -322.95523071289062 - 30 -0.0 - 10 -469.11541748046875 - 20 -321.50009155273437 - 30 -0.0 - 10 -470.45071411132812 - 20 -320.01547241210937 - 30 -0.0 - 10 -471.74700927734375 - 20 -318.5042724609375 - 30 -0.0 - 10 -473.00244140625 - 20 -316.96261596679687 - 30 -0.0 - 10 -474.21804809570312 - 20 -315.39700317382812 - 30 -0.0 - 10 -475.3892822265625 - 20 -313.8031005859375 - 30 -0.0 - 10 -476.52069091796875 - 20 -312.18508911132812 - 30 -0.0 - 10 -477.61239624023437 - 20 -310.5430908203125 - 30 -0.0 - 10 -478.65994262695312 - 20 -308.87734985351563 - 30 -0.0 - 10 -479.66604614257812 - 20 -307.18856811523437 - 30 -0.0 - 10 -480.62994384765625 - 20 -305.4794921875 - 30 -0.0 - 10 -481.55062866210937 - 20 -303.74853515625 - 30 -0.0 - 10 -482.43017578125 - 20 -301.99908447265625 - 30 -0.0 - 10 -483.26461791992187 - 20 -300.22860717773437 - 30 -0.0 - 10 -484.0562744140625 - 20 -298.44070434570312 - 30 -0.0 - 10 -484.80484008789062 - 20 -296.63531494140625 - 30 -0.0 - 10 -485.5115966796875 - 20 -294.81423950195312 - 30 -0.0 - 10 -486.17178344726562 - 20 -292.97775268554688 - 30 -0.0 - 10 -486.78836059570312 - 20 -291.1265869140625 - 30 -0.0 - 10 -487.35946655273438 - 20 -289.26177978515625 - 30 -0.0 - 10 -487.88690185546875 - 20 -287.3822021484375 - 30 -0.0 - 10 -488.36993408203125 - 20 -285.49075317382812 - 30 -0.0 - 10 -488.80776977539062 - 20 -283.59017944335937 - 30 -0.0 - 10 -489.19937133789062 - 20 -281.6787109375 - 30 -0.0 - 10 -489.5458984375 - 20 -279.7581787109375 - 30 -0.0 - 10 -489.84439086914062 - 20 -277.82769775390625 - 30 -0.0 - 10 -490.09869384765625 - 20 -275.88986206054687 - 30 -0.0 - 10 -490.30718994140625 - 20 -273.94573974609375 - 30 -0.0 - 10 -490.36663818359375 - 20 -273.23193359375 - 30 -0.0 - 10 -505.23043823242187 - 20 -264.650390625 - 30 -0.0 - 10 -505.19219970703125 - 20 -265.31121826171875 - 30 -0.0 - 10 -505.19219970703125 - 20 -265.31121826171875 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5E -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -49 - 70 -0 - 10 -431.49996948242187 - 20 -315.08746337890625 - 30 -0.0 - 10 -431.50997924804687 - 20 -314.90997314453125 - 30 -0.0 - 10 -431.53497314453125 - 20 -314.7349853515625 - 30 -0.0 - 10 -431.57748413085937 - 20 -314.56747436523437 - 30 -0.0 - 10 -431.63748168945312 - 20 -314.407470703125 - 30 -0.0 - 10 -431.7974853515625 - 20 -314.1099853515625 - 30 -0.0 - 10 -432.01248168945312 - 20 -313.8499755859375 - 30 -0.0 - 10 -432.26998901367187 - 20 -313.63748168945312 - 30 -0.0 - 10 -432.56747436523437 - 20 -313.4749755859375 - 30 -0.0 - 10 -432.72998046875 - 20 -313.41748046875 - 30 -0.0 - 10 -432.8974609375 - 20 -313.37246704101562 - 30 -0.0 - 10 -433.06997680664062 - 20 -313.34747314453125 - 30 -0.0 - 10 -433.24996948242187 - 20 -313.33746337890625 - 30 -0.0 - 10 -433.42996215820312 - 20 -313.34747314453125 - 30 -0.0 - 10 -433.60247802734375 - 20 -313.37246704101562 - 30 -0.0 - 10 -433.76998901367187 - 20 -313.41748046875 - 30 -0.0 - 10 -433.93246459960937 - 20 -313.4749755859375 - 30 -0.0 - 10 -434.22998046875 - 20 -313.63748168945312 - 30 -0.0 - 10 -434.48748779296875 - 20 -313.8499755859375 - 30 -0.0 - 10 -434.70248413085937 - 20 -314.1099853515625 - 30 -0.0 - 10 -434.86248779296875 - 20 -314.407470703125 - 30 -0.0 - 10 -434.9224853515625 - 20 -314.56747436523437 - 30 -0.0 - 10 -434.9649658203125 - 20 -314.7349853515625 - 30 -0.0 - 10 -434.989990234375 - 20 -314.90997314453125 - 30 -0.0 - 10 -434.99996948242187 - 20 -315.08746337890625 - 30 -0.0 - 10 -434.989990234375 - 20 -315.26748657226563 - 30 -0.0 - 10 -434.9649658203125 - 20 -315.43997192382812 - 30 -0.0 - 10 -434.9224853515625 - 20 -315.60748291015625 - 30 -0.0 - 10 -434.86248779296875 - 20 -315.76998901367187 - 30 -0.0 - 10 -434.70248413085937 - 20 -316.06747436523437 - 30 -0.0 - 10 -434.48748779296875 - 20 -316.32498168945312 - 30 -0.0 - 10 -434.22998046875 - 20 -316.53997802734375 - 30 -0.0 - 10 -433.93246459960937 - 20 -316.69998168945312 - 30 -0.0 - 10 -433.76998901367187 - 20 -316.75997924804687 - 30 -0.0 - 10 -433.60247802734375 - 20 -316.802490234375 - 30 -0.0 - 10 -433.42996215820312 - 20 -316.82748413085937 - 30 -0.0 - 10 -433.24996948242187 - 20 -316.83746337890625 - 30 -0.0 - 10 -433.06997680664062 - 20 -316.82748413085937 - 30 -0.0 - 10 -432.8974609375 - 20 -316.802490234375 - 30 -0.0 - 10 -432.72998046875 - 20 -316.75997924804687 - 30 -0.0 - 10 -432.56747436523437 - 20 -316.69998168945312 - 30 -0.0 - 10 -432.26998901367187 - 20 -316.53997802734375 - 30 -0.0 - 10 -432.01248168945312 - 20 -316.32498168945312 - 30 -0.0 - 10 -431.7974853515625 - 20 -316.06747436523437 - 30 -0.0 - 10 -431.63748168945312 - 20 -315.76998901367187 - 30 -0.0 - 10 -431.57748413085937 - 20 -315.60748291015625 - 30 -0.0 - 10 -431.53497314453125 - 20 -315.43997192382812 - 30 -0.0 - 10 -431.50997924804687 - 20 -315.26748657226563 - 30 -0.0 - 10 -431.49996948242187 - 20 -315.08746337890625 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5F -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -49 - 70 -0 - 10 -464.99996948242187 - 20 -315.0899658203125 - 30 -0.0 - 10 -465.00997924804687 - 20 -314.90997314453125 - 30 -0.0 - 10 -465.03497314453125 - 20 -314.73748779296875 - 30 -0.0 - 10 -465.07748413085937 - 20 -314.56997680664062 - 30 -0.0 - 10 -465.13748168945312 - 20 -314.407470703125 - 30 -0.0 - 10 -465.2974853515625 - 20 -314.1099853515625 - 30 -0.0 - 10 -465.51248168945312 - 20 -313.85247802734375 - 30 -0.0 - 10 -465.76998901367187 - 20 -313.63748168945312 - 30 -0.0 - 10 -466.06747436523437 - 20 -313.47747802734375 - 30 -0.0 - 10 -466.22998046875 - 20 -313.41748046875 - 30 -0.0 - 10 -466.3974609375 - 20 -313.37496948242187 - 30 -0.0 - 10 -466.56997680664062 - 20 -313.3499755859375 - 30 -0.0 - 10 -466.74996948242187 - 20 -313.3399658203125 - 30 -0.0 - 10 -466.92996215820312 - 20 -313.3499755859375 - 30 -0.0 - 10 -467.10247802734375 - 20 -313.37496948242187 - 30 -0.0 - 10 -467.26998901367187 - 20 -313.41748046875 - 30 -0.0 - 10 -467.43246459960937 - 20 -313.47747802734375 - 30 -0.0 - 10 -467.72998046875 - 20 -313.63748168945312 - 30 -0.0 - 10 -467.98748779296875 - 20 -313.85247802734375 - 30 -0.0 - 10 -468.20248413085937 - 20 -314.1099853515625 - 30 -0.0 - 10 -468.36248779296875 - 20 -314.407470703125 - 30 -0.0 - 10 -468.4224853515625 - 20 -314.56997680664062 - 30 -0.0 - 10 -468.4649658203125 - 20 -314.73748779296875 - 30 -0.0 - 10 -468.48995971679687 - 20 -314.90997314453125 - 30 -0.0 - 10 -468.49996948242187 - 20 -315.0899658203125 - 30 -0.0 - 10 -468.48995971679687 - 20 -315.26998901367187 - 30 -0.0 - 10 -468.4649658203125 - 20 -315.44247436523437 - 30 -0.0 - 10 -468.4224853515625 - 20 -315.6099853515625 - 30 -0.0 - 10 -468.36248779296875 - 20 -315.77249145507812 - 30 -0.0 - 10 -468.20248413085937 - 20 -316.06997680664062 - 30 -0.0 - 10 -467.98748779296875 - 20 -316.32748413085937 - 30 -0.0 - 10 -467.72998046875 - 20 -316.54248046875 - 30 -0.0 - 10 -467.43246459960937 - 20 -316.70248413085937 - 30 -0.0 - 10 -467.26998901367187 - 20 -316.76248168945312 - 30 -0.0 - 10 -467.10247802734375 - 20 -316.80499267578125 - 30 -0.0 - 10 -466.92996215820312 - 20 -316.82998657226562 - 30 -0.0 - 10 -466.74996948242187 - 20 -316.8399658203125 - 30 -0.0 - 10 -466.56997680664062 - 20 -316.82998657226562 - 30 -0.0 - 10 -466.3974609375 - 20 -316.80499267578125 - 30 -0.0 - 10 -466.22998046875 - 20 -316.76248168945312 - 30 -0.0 - 10 -466.06747436523437 - 20 -316.70248413085937 - 30 -0.0 - 10 -465.76998901367187 - 20 -316.54248046875 - 30 -0.0 - 10 -465.51248168945312 - 20 -316.32748413085937 - 30 -0.0 - 10 -465.2974853515625 - 20 -316.06997680664062 - 30 -0.0 - 10 -465.13748168945312 - 20 -315.77249145507812 - 30 -0.0 - 10 -465.07748413085937 - 20 -315.6099853515625 - 30 -0.0 - 10 -465.03497314453125 - 20 -315.44247436523437 - 30 -0.0 - 10 -465.00997924804687 - 20 -315.26998901367187 - 30 -0.0 - 10 -464.99996948242187 - 20 -315.0899658203125 - 30 -0.0 - 0 -LWPOLYLINE - 5 -60 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -49 - 70 -0 - 10 -431.49746704101562 - 20 -264.58749389648437 - 30 -0.0 - 10 -431.50747680664062 - 20 -264.407470703125 - 30 -0.0 - 10 -431.532470703125 - 20 -264.2349853515625 - 30 -0.0 - 10 -431.57748413085937 - 20 -264.06747436523437 - 30 -0.0 - 10 -431.63497924804687 - 20 -263.90496826171875 - 30 -0.0 - 10 -431.7974853515625 - 20 -263.60748291015625 - 30 -0.0 - 10 -432.00997924804687 - 20 -263.3499755859375 - 30 -0.0 - 10 -432.26998901367187 - 20 -263.13497924804688 - 30 -0.0 - 10 -432.56747436523437 - 20 -262.9749755859375 - 30 -0.0 - 10 -432.72747802734375 - 20 -262.91497802734375 - 30 -0.0 - 10 -432.89498901367187 - 20 -262.87246704101562 - 30 -0.0 - 10 -433.06997680664062 - 20 -262.84747314453125 - 30 -0.0 - 10 -433.24746704101562 - 20 -262.83749389648438 - 30 -0.0 - 10 -433.427490234375 - 20 -262.84747314453125 - 30 -0.0 - 10 -433.5999755859375 - 20 -262.87246704101562 - 30 -0.0 - 10 -433.76748657226562 - 20 -262.91497802734375 - 30 -0.0 - 10 -433.92996215820313 - 20 -262.9749755859375 - 30 -0.0 - 10 -434.22747802734375 - 20 -263.13497924804688 - 30 -0.0 - 10 -434.4849853515625 - 20 -263.3499755859375 - 30 -0.0 - 10 -434.69998168945312 - 20 -263.60748291015625 - 30 -0.0 - 10 -434.8599853515625 - 20 -263.90496826171875 - 30 -0.0 - 10 -434.91998291015625 - 20 -264.06747436523437 - 30 -0.0 - 10 -434.96246337890625 - 20 -264.2349853515625 - 30 -0.0 - 10 -434.98748779296875 - 20 -264.407470703125 - 30 -0.0 - 10 -434.99746704101562 - 20 -264.58749389648437 - 30 -0.0 - 10 -434.98748779296875 - 20 -264.76748657226562 - 30 -0.0 - 10 -434.96246337890625 - 20 -264.93997192382812 - 30 -0.0 - 10 -434.91998291015625 - 20 -265.10748291015625 - 30 -0.0 - 10 -434.8599853515625 - 20 -265.26998901367187 - 30 -0.0 - 10 -434.69998168945312 - 20 -265.56747436523437 - 30 -0.0 - 10 -434.4849853515625 - 20 -265.82498168945312 - 30 -0.0 - 10 -434.22747802734375 - 20 -266.03997802734375 - 30 -0.0 - 10 -433.92996215820313 - 20 -266.19998168945312 - 30 -0.0 - 10 -433.76748657226562 - 20 -266.25997924804687 - 30 -0.0 - 10 -433.5999755859375 - 20 -266.302490234375 - 30 -0.0 - 10 -433.427490234375 - 20 -266.32748413085937 - 30 -0.0 - 10 -433.24746704101562 - 20 -266.33749389648437 - 30 -0.0 - 10 -433.06997680664062 - 20 -266.32748413085937 - 30 -0.0 - 10 -432.89498901367187 - 20 -266.302490234375 - 30 -0.0 - 10 -432.72747802734375 - 20 -266.25997924804687 - 30 -0.0 - 10 -432.56747436523437 - 20 -266.19998168945312 - 30 -0.0 - 10 -432.26998901367187 - 20 -266.03997802734375 - 30 -0.0 - 10 -432.00997924804687 - 20 -265.82498168945312 - 30 -0.0 - 10 -431.7974853515625 - 20 -265.56747436523437 - 30 -0.0 - 10 -431.63497924804687 - 20 -265.26998901367187 - 30 -0.0 - 10 -431.57748413085937 - 20 -265.10748291015625 - 30 -0.0 - 10 -431.532470703125 - 20 -264.93997192382812 - 30 -0.0 - 10 -431.50747680664062 - 20 -264.76748657226562 - 30 -0.0 - 10 -431.49746704101562 - 20 -264.58749389648437 - 30 -0.0 - 0 -LWPOLYLINE - 5 -61 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -49 - 70 -0 - 10 -464.99996948242187 - 20 -264.6524658203125 - 30 -0.0 - 10 -465.00997924804687 - 20 -264.47247314453125 - 30 -0.0 - 10 -465.03497314453125 - 20 -264.29998779296875 - 30 -0.0 - 10 -465.07748413085937 - 20 -264.13247680664062 - 30 -0.0 - 10 -465.13748168945312 - 20 -263.969970703125 - 30 -0.0 - 10 -465.2974853515625 - 20 -263.6724853515625 - 30 -0.0 - 10 -465.51248168945312 - 20 -263.41497802734375 - 30 -0.0 - 10 -465.76998901367187 - 20 -263.19998168945312 - 30 -0.0 - 10 -466.06747436523437 - 20 -263.03997802734375 - 30 -0.0 - 10 -466.22998046875 - 20 -262.97998046875 - 30 -0.0 - 10 -466.3974609375 - 20 -262.93746948242187 - 30 -0.0 - 10 -466.56997680664062 - 20 -262.9124755859375 - 30 -0.0 - 10 -466.74996948242187 - 20 -262.9024658203125 - 30 -0.0 - 10 -466.92996215820312 - 20 -262.9124755859375 - 30 -0.0 - 10 -467.10247802734375 - 20 -262.93746948242187 - 30 -0.0 - 10 -467.26998901367187 - 20 -262.97998046875 - 30 -0.0 - 10 -467.43246459960937 - 20 -263.03997802734375 - 30 -0.0 - 10 -467.72998046875 - 20 -263.19998168945312 - 30 -0.0 - 10 -467.98748779296875 - 20 -263.41497802734375 - 30 -0.0 - 10 -468.20248413085937 - 20 -263.6724853515625 - 30 -0.0 - 10 -468.36248779296875 - 20 -263.969970703125 - 30 -0.0 - 10 -468.4224853515625 - 20 -264.13247680664062 - 30 -0.0 - 10 -468.4649658203125 - 20 -264.29998779296875 - 30 -0.0 - 10 -468.48995971679687 - 20 -264.47247314453125 - 30 -0.0 - 10 -468.49996948242187 - 20 -264.6524658203125 - 30 -0.0 - 10 -468.48995971679687 - 20 -264.83248901367187 - 30 -0.0 - 10 -468.4649658203125 - 20 -265.00497436523437 - 30 -0.0 - 10 -468.4224853515625 - 20 -265.1724853515625 - 30 -0.0 - 10 -468.36248779296875 - 20 -265.33499145507812 - 30 -0.0 - 10 -468.20248413085937 - 20 -265.63247680664062 - 30 -0.0 - 10 -467.98748779296875 - 20 -265.88998413085937 - 30 -0.0 - 10 -467.72998046875 - 20 -266.10498046875 - 30 -0.0 - 10 -467.43246459960937 - 20 -266.26498413085937 - 30 -0.0 - 10 -467.26998901367187 - 20 -266.32498168945312 - 30 -0.0 - 10 -467.10247802734375 - 20 -266.36749267578125 - 30 -0.0 - 10 -466.92996215820312 - 20 -266.39248657226562 - 30 -0.0 - 10 -466.74996948242187 - 20 -266.4024658203125 - 30 -0.0 - 10 -466.56997680664062 - 20 -266.39248657226562 - 30 -0.0 - 10 -466.3974609375 - 20 -266.36749267578125 - 30 -0.0 - 10 -466.22998046875 - 20 -266.32498168945312 - 30 -0.0 - 10 -466.06747436523437 - 20 -266.26498413085937 - 30 -0.0 - 10 -465.76998901367187 - 20 -266.10498046875 - 30 -0.0 - 10 -465.51248168945312 - 20 -265.88998413085937 - 30 -0.0 - 10 -465.2974853515625 - 20 -265.63247680664062 - 30 -0.0 - 10 -465.13748168945312 - 20 -265.33499145507812 - 30 -0.0 - 10 -465.07748413085937 - 20 -265.1724853515625 - 30 -0.0 - 10 -465.03497314453125 - 20 -265.00497436523437 - 30 -0.0 - 10 -465.00997924804687 - 20 -264.83248901367187 - 30 -0.0 - 10 -464.99996948242187 - 20 -264.6524658203125 - 30 -0.0 - 0 -ENDSEC - 0 -SECTION - 2 -OBJECTS - 0 -DICTIONARY - 5 -C -100 -AcDbDictionary -280 -0 -281 -1 - 3 -ACAD_GROUP -350 -D - 3 -ACAD_LAYOUT -350 -1A - 3 -ACAD_MLINESTYLE -350 -17 - 3 -ACAD_PLOTSETTINGS -350 -19 - 3 -ACAD_PLOTSTYLENAME -350 -E - 3 -AcDbVariableDictionary -350 -62 - 0 -DICTIONARY - 5 -D -100 -AcDbDictionary -280 -0 -281 -1 - 0 -ACDBDICTIONARYWDFLT - 5 -E -100 -AcDbDictionary -281 -1 - 3 -Normal -350 -F -100 -AcDbDictionaryWithDefault -340 -F - 0 -ACDBPLACEHOLDER - 5 -F - 0 -DICTIONARY - 5 -17 -100 -AcDbDictionary -280 -0 -281 -1 - 3 -Standard -350 -18 - 0 -MLINESTYLE - 5 -18 -100 -AcDbMlineStyle - 2 -STANDARD - 70 -0 - 3 - - 62 -256 - 51 -90.0 - 52 -90.0 - 71 -2 - 49 -0.5 - 62 -256 - 6 -BYLAYER - 49 --0.5 - 62 -256 - 6 -BYLAYER - 0 -DICTIONARY - 5 -19 -100 -AcDbDictionary -280 -0 -281 -1 - 0 -DICTIONARY - 5 -1A -100 -AcDbDictionary -281 -1 - 3 -Layout1 -350 -1E - 3 -Layout2 -350 -26 - 3 -Model -350 -22 - 0 -LAYOUT - 5 -1E -100 -AcDbPlotSettings - 1 - - 2 -none_device - 4 - - 6 - - 40 -0.0 - 41 -0.0 - 42 -0.0 - 43 -0.0 - 44 -0.0 - 45 -0.0 - 46 -0.0 - 47 -0.0 - 48 -0.0 - 49 -0.0 -140 -0.0 -141 -0.0 -142 -1.0 -143 -1.0 - 70 -688 - 72 -0 - 73 -0 - 74 -5 - 7 - - 75 -16 -147 -1.0 -148 -0.0 -149 -0.0 -100 -AcDbLayout - 1 -Layout1 - 70 -1 - 71 -1 - 10 -0.0 - 20 -0.0 - 11 -420.0 - 21 -297.0 - 12 -0.0 - 22 -0.0 - 32 -0.0 - 14 -100000000000000000000.0 - 24 -100000000000000000000.0 - 34 -100000000000000000000.0 - 15 --100000000000000000000.0 - 25 --100000000000000000000.0 - 35 --100000000000000000000.0 -146 -0.0 - 13 -0.0 - 23 -0.0 - 33 -0.0 - 16 -1.0 - 26 -0.0 - 36 -0.0 - 17 -0.0 - 27 -1.0 - 37 -0.0 - 76 -0 -330 -1B - 0 -LAYOUT - 5 -22 -100 -AcDbPlotSettings - 1 - - 2 -none_device - 4 - - 6 - - 40 -0.0 - 41 -0.0 - 42 -0.0 - 43 -0.0 - 44 -0.0 - 45 -0.0 - 46 -0.0 - 47 -0.0 - 48 -0.0 - 49 -0.0 -140 -0.0 -141 -0.0 -142 -1.0 -143 -1.0 - 70 -1712 - 72 -0 - 73 -0 - 74 -0 - 7 - - 75 -0 -147 -1.0 -148 -0.0 -149 -0.0 -100 -AcDbLayout - 1 -Model - 70 -1 - 71 -0 - 10 -0.0 - 20 -0.0 - 11 -12.0 - 21 -9.0 - 12 -0.0 - 22 -0.0 - 32 -0.0 - 14 -0.0 - 24 -0.0 - 34 -0.0 - 15 -0.0 - 25 -0.0 - 35 -0.0 -146 -0.0 - 13 -0.0 - 23 -0.0 - 33 -0.0 - 16 -1.0 - 26 -0.0 - 36 -0.0 - 17 -0.0 - 27 -1.0 - 37 -0.0 - 76 -0 -330 -1F - 0 -LAYOUT - 5 -26 -100 -AcDbPlotSettings - 1 - - 2 -none_device - 4 - - 6 - - 40 -0.0 - 41 -0.0 - 42 -0.0 - 43 -0.0 - 44 -0.0 - 45 -0.0 - 46 -0.0 - 47 -0.0 - 48 -0.0 - 49 -0.0 -140 -0.0 -141 -0.0 -142 -1.0 -143 -1.0 - 70 -688 - 72 -0 - 73 -0 - 74 -5 - 7 - - 75 -16 -147 -1.0 -148 -0.0 -149 -0.0 -100 -AcDbLayout - 1 -Layout2 - 70 -1 - 71 -2 - 10 -0.0 - 20 -0.0 - 11 -12.0 - 21 -9.0 - 12 -0.0 - 22 -0.0 - 32 -0.0 - 14 -0.0 - 24 -0.0 - 34 -0.0 - 15 -0.0 - 25 -0.0 - 35 -0.0 -146 -0.0 - 13 -0.0 - 23 -0.0 - 33 -0.0 - 16 -1.0 - 26 -0.0 - 36 -0.0 - 17 -0.0 - 27 -1.0 - 37 -0.0 - 76 -0 -330 -23 - 0 -DICTIONARY - 5 -62 -100 -AcDbDictionary -281 -1 - 3 -DIMASSOC -350 -64 - 3 -HIDETEXT -350 -63 - 0 -DICTIONARYVAR - 5 -63 -100 -DictionaryVariables -280 -0 - 1 -2 - 0 -DICTIONARYVAR - 5 -64 -100 -DictionaryVariables -280 -0 - 1 -1 - 0 -ENDSEC - 0 -EOF diff --git a/莱洛三角切割/triangle.lcp b/莱洛三角切割/triangle.lcp deleted file mode 100644 index 3dadd0575f9a0b61b2d7c99d3bbc35033b262b57..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 16753 zcmbW8cUVr#KtnOWstYwwx85B3`n*sX>}qp5}83V!Q; zF@OGVjYjx={+W57>VG8+Rmbr+&;S38%b9-j)OqqB8cj|7{lDgG468qPlYjqX=d*G1 z>NWUF{`%kXsq4S%*n6z{si9w>ggiRgEQ&O5G%67Xbg zK9!vSnBB@J-)z9*Rt04Ll1D-c$e`9%Qnnl_pyI}W0a*oY5d+5$^6+tj3%=yI9S_byu;P z*W#pNHPdN#i`Co*Ji`d9k@=yR!daiXRmBv_ifJ_Wq=s_DpnMA{b{~sr-~|A$%9;sa zJHG7!Y&q-EW=IELd-ej@dq60F<1umsaD;JhHeoqpHcA0-7G;|NoL59RfHQR)0I);u z0UZFVp+;z10PC~11%MTcGXkg@0$5c!!aB=2th`*swUBnWI?^)NOZwspO7C1#84p)k zM#y!SF>@!#EVwshUfeA*Q|=#`J9m^+gL_Qs!(As8(*U>+5vmFcxH<8!e|~+=n(D5f zK5py`b%LRvC1B2qJPQ3`BWX^pLKm*sNXqo}=-r(Fz3s4j3}76aN6H02@L7a@3s8Im z5$6Mf9^}!e`+)c=H2MR80XH#^%yGz9=ji!C0$vr^Kfl_}=zP_3c^HIaUolhjRqw^& z`7$0kVi1gvcurIgKrmJrxmVjsvjVW?lg$9^%f23fy@%HTa6E2$0FF?OaLjTJXCYT{ zUaB2rDlK#F(if{Cz3cQ*bnsuQT%=RENT)KIQB}D}r*e@_WwfxWa* zbt>bU;7aKE;ZjglF4n1BtWz0Rq^dHmW3F*=I4;B=05MZ>L8~g`VpUa!9d~>b*dJH6 zsxs^}!^j*5T=c5SxS&;)k%g*qkxu0zoyy3IR~g3^=~PBuY6WWl~ptt!%~tm*@m zRrn&64_}|+_jxa;qnDG9ZY7PuYTS^o;s%(4daf-51aXC51Hw@AQMI&RQlpxmfpFSIUd=|Cx5S=^L7b< zdpZ1j0Na`U4S+3&4g#>Rh(G{)Pa^=wv$hL>Ba|Z?vz)`dELU+}(hg@TEpzVD7poz? z>-14{@I@*=aPF)Bxyo9U$mkeU4ny_AS!D~ zUgmfd9+7$SoPebmF~F*1R+;Tcb=b1hi+yFW%Iw`-063mvR+%G|BOJ4w!&%5xoR?~6 z8}eeyoV)bJYDn)oeH0yhk;*GniSehQpFjSL-&RPYoOYm>_A_f#*SSN5Pt#N zSH*T@b*+%X?*a6(3TaO|z~XKpWt{{B6=2mKKwx1ZyiR`tXQU zjOR!Vd6iU^?MR*3vQ(aZ$y%^?Ssjjt>m?&R*$Kcg+xG-iAd69h0i4&K(E!dg?ppxo zo;DG{YA93qBi4t36_X>Zp`632%2lkhY6r?o%UlcTi>o8O>-t9)jsyFmE`0K@E=+He zOS6yQtgCg)rHGw4Y(#g-rGPbn^j^6XItO4pIG5Ij0W3!4QgRT$@9SK8>kF73f>ri_ zuy1q8h|elKvZo4%I-cY92*9gCZvog&R04o4Cm#T?uj0)B_P%Ece}s7AegtGU&830k zd5(fP!vJCBcPOq8ATs9;g?0rPpT9$+Is+==?~tz-AUo;~8F&D~BJN--;*X|Qk1QEc zJtwSN^{VprIy!QGHcZ%Th|iVokJNDP?gN8hDmc6nCMYf2pd)lAfiiI*|iP z$!HKhiXT#{Dp))mtGElZM_@8{A&OU;O%{K8xGLkyH84AK+v`ObdtL;`_z4k<1RcEbD!377Y44qPouaC zvuE9>Q0~I8Z>vWF`&ZA=`c$uqx6#>YT5UN-Q|&9PyhQar{cedGk8xUw8evRAi5m0t zVw)J*lZm#Dd?M`IPMksXDPSRWpdit!xTg}h3t%64QIvSrzY>`T^y zz02xwJX|kalO=dc1aQnz+=bc5B8|I{^D-&{aHi%@0Gzw;a{#Lm&Rr<=;VxvwPYXp{*i^_z`m#p3;xxG!Po(#I&8p`QY`P18xT5n$ZXurk0D9Pw-^Kwd0B&2VN0Jv+&)G8tz^fvL1K5s1 zHvn69a{;igfo1^qZd9K?LOkXl*Fi7b^OK(dwAcj(<^y;~HqQX?PLXvPz54fVb0qdnnMELWQkj<@_Ewpx1$JARdpR~@sYZo4CbK>~A{FB~QbS%PRb@L; zXSOVrXJ4`w>|Iue&~h?eMW=00C2TC@~IDStpme-2|BLyo>$@ z{M9j^JU;@;ZWNG>-f>cHOemrwpD>cF+@q4G0H;kQR67eW$FY>U`~~no_kad22Rs`1 zh^7w)l-_$x*~Wmu-xMEU4N!Ovqr;YC@z!zZE@B^LL1)+BT@{zo&prQ7~C)(a0P(Qeennpq1 zystGP`3?l{qbQ=09bjgaMg*KenZ{LUgoX8fEPtXAPgbLpiFY(&`+F3(#d(d``E3j- z2li{kyPIf$eJeB~(|;E!e}=-~5j4p=UyWFAjU)B!CK|CX3XK$o{>5dNn6!o5NUs_Gd!Q6M$_Ulz>EyH(IvuXui(@_Pr+P<8Wy+Y2KmLT62RTB{>OURjK5(C+2Tdd8MDG&n6*>jE-!Gon9DneNzo zjfVC??xnw_lf_D?QF}=mbQ^!-FYaQ6b*dYnga*I)V$kiD>gBAua5`5zb=1_=ARfbN9?vTqj9`RM?^ zM+M|C6TtWQ)3X73%?s5LW2ZuO&JrqAR|O3%thO_^P_@i=bm^=3WTEOkIK5Df#{fII zjBpP2e;IRpexaHL@Bf^a!Xv#_19;BduK~Pjt0#c%>}vpE%X1S^b@sJxJ|GOGK17x>CU@HNqYGLwH zK;ZL48Wq7G-ASaAivh;x6KUWQKu~-l*)Ip&+mcAWYx$!Hz-B=7v_wkV1xW9O<$nWC zIVDnD9w4YWKGH{E@eLDck1-(dt3)z)0L-b8NM(M2as{gf1EK-u-vQk96KU-NfI)3| z-w3d%pNMBrhGzKa93b8-k?P$B_;pOAtoMM(;V{@7ItS0gs&)YP-xBGqCm?<=Ty*9V zoJJM|@VkKoyYfe+u+t4N{Zk@^3xIpmBz*q^h_Owgh>rYGCx8n;SJQvsi#o&2)$@OK zhIUaE-t+AzP5hK9iue;U6%PmO1cZ03Qi~Mdt_okfV8pj&6(j)6sZm9H7!00P;#kQa z?Vy^_*eG5A(elrtd8 z3#+;TlHDt5_6UI1t&)7F0nz|*5rAONN-~cIWP9VILjYg@N;;VWC=RTowb_8Ev6VEc z5)eEOt4yJnb~h$_v6Ls^lywhJ1@r_I7gbVmfBvWf!4Co$HK@Wt29Rx4MR9`x0bW&P z9>gE@LGFD4YrlppJpiFUR;fjDkE)_#JB%zjg~TkR!#^V17g5Q!!=xF%q?r1wJB+fReNu>fpqT|qB5K-?ky z-;rreK=|+P=vf}LXk++-8Z6#Nig@vy8m)hct9JK>xr4ny~`#=2$5m zJ^^_B_kHru2Ru4oLK#&6=d^p&wI$+NoKZ|o+X0+%iYSHaHy7Je5AJWDdj(WG0FeA3 zpGI~C7?$B%NpC>?=Xa?s-E}@UIKZJg+2lDN zFug$*8TSM@Hp`?94FNk_-=?jp$f9A}Thx6q;5VlX3ibdr_PR-}3n9W?af3n@11kGp zr%qOYqhqd-!$~N%>S8+0n+`bNrFHvlJ2yQy~GOfA;RRsiDCGH6HuTB6+QHl?lw zES!-^cdi4rre~4ISLmo!);UzO1K{?YJM>*J!1h)y`OXHUJLJ*+wSYQ{@@dajz_T1| zsk;EW?)?Y8=o-lQ=OQrl;~$(Db@M9K^WH@o$Gd>bcviD|ca`kZa4ad@xqb&UqPZy;szzH1cO6{q+arq`+K5S-$jqOMcr zgx{c-=?zMpABhL4y*KFI=CycYaKA|xj;|r5|D~JsP0nf*U~C38&;zXbltD30t4Mjd z^%lJwy^@r5;x>hESOFL1x2f5U=()4mL@$=& zDxH%8ye!JX`SadM<=`G(B#cHN5|P@)6KnjP$)4&TQ9?b`eN%$YC9bV z>dU6LDfSy2sD0@Imnmf_YH@kZB}%)F>O8M|iS$fRxWbhesWJ?ujBas}uAD$|^hrV{PXiP@gSO{$M*9ySV8~X9CDu44@O5N8=oiJ1L(2;6r|8pJv zJCs7s!|;H(V0jAdi{Ar%CZ*83+I#VxbVv%7EduCz^&j}6j(7L?eu=fgk?e== zC5_MQk91r=23PHnk2E?SzJJhuB#U4~Gve(Ba;lGuq3GlXdUXa7FZ%HV4Va1?n%jS% z4Q+4@q~3Z@({qsL=^5{7Oe8X|YxJIqd!ggM`|}+oe+5z6d%h!2et(j2s)B|uN2A+$ zRgiZ-NLdy8mTdWPb&$zhvM5G>XDoa}$%jw?^WxXEb0JDn*zq+54MUN-E`LR?OHAM`=g*dqG!kqu8$&KBwOjQ2wO2XVfna4Y4odDS7Wii;Q_uPE)s_ zY5IOuPJ=e0jV?7Wqd}X|SQ9LsQ2KVXnzPkoN;rt-dtvg3W+tE=?VCKLoGdixh^kVm zEJMpKExAv*?s%m2O(~&O%hA@Ix85V?GBmpVxne3hk0(bh;O~)e@oDZoYFq^Pc0dUQ z&xQBK7WXN^4DoDvbf3OS0lbebrA|{2>Z-{P$lCz6 z7nvUNdQ3Gd0bBDQ)Awg_N%x!ogf19x`vq;h zfWp-r|AJy;QOeopUeJY&X#GzpLG~}G^22d2>FN~JT|f3E%?(B;L_B{0 zc3p4{gp7YhKe(Z77H@t<=5}bLf|OVE$`q~D?8z%?V1$cdr@?D#(EwdHz~(i*sD(Z( zcY00zz6Q+u{UaqDz%`)j-hbeWu7S^g;-NmSfsC`6l=D5_1~P1Twu!>FWTzN&?%Fz?S74ov(!o9P@A8ug_WcV@CfD z^wzuww1Wd>7{!6Mx%Yq$aG(XFAF2?2ry3snK2ql}@G5a=zRTGfpV66&`DC!v9^ehm55&fU~MF@S`t`4IfsE)Nktzz19;Ass|b`= zNnkq?*oB;<^YwoYbP;-F{u@tmFs>zO{#xWIcI6u5_}I`>v~JOil&kAK#F&sKcnWFm zAr_o#h^MQK?qY*OecbArx{Iaz>f&YFayRkRwGJu6G;U&WdQI#j(_BT+EPdRf3S2}d zPX(vXo-QJ)PNlyx_egtj|J*x&CAE2bG2r*t{)*)+XK{S4ICecr$} z;^W`QeMg#=NV2O(ibEeOF?Boid2`)T^s{J$9}yj9DVz>M!;d8vVmU$8wLe;jAB&;0 zZ#@ffePv5hdh9kAd;CmDN$6rO!akbeOM_xFQ7^%glx4q~iDxU?;<)H$CR&cQCB?ef zR9x}V;$F4ERQzn_g!6hIQ!%?vds6`612+I5&BtC`J_yj%)Qau7fI+ER@$xO89%@w+|Lh^XTwN}ocgS(m&-iye^e!_tmolg~G}th##(>mNW-khqFFn z$r_ZP1aN3Iz%s!{bnpc9KI0>5G)0-t9P<(H%7#F(KYYaLi$PFzqmM}1)gOn81wO)V zULWlIAwI%>L{Aj1tB=^$p$86MWP7ZUkA)-?kzOy+_9NwbQInTU2sHN)=~8Tu^lN5d^!r_$qx8Q-UnWy^8`CQzOMEX z^qn;+xz1kVL%0>bd`Rsede1Y5opBw+SCJ;P;7hi&&wp~3_ue^WCSq0cNYd1|G8MT! zMw0$`cT@dL7_krk8dU zsV!hWf>vYUB=9vAhY1!ka=;p$V|C^ zWbWKiQVs4gsSkIZR7}^0iVha=nf&wf_~)!Un}2?P;Qsm}ZwADMYQ@1=!1(D}VR9PKY@SwZP5>k=s~(xP zzIsmQZPlxa_Ui1!R$F#ETJ3Ai@oMj}C)9Wp9+|Zt=MJ8;c|PC?R;?ZeU^`VF0Jfaj z62QKW*95Tl?iJ2zJXc-#OH<-d4S;Xs^yrY_(;#qt(9F9Iy5s zdqRx|Dm&^_hGkV{*ilt>)TzuDt5n%hr?R6?Wmr~Kt{#aEt)BBFxO!EO!8$vAt1Z6? zsP?s`TebIDU902K!569g`Ew@s@^19<c=H9ek0>|Nbuk15m5g!=UmsRImF|WR;3~+8qHjLxo*)0A{H9 zIaWCdUGSJyjzC|0kY?f$N6|P4M|8~~ zC$Y~7;PJ*uyr{rg{pN;tV$)GTrH3<4_<*^$okjjfoZdVB&|VB%#?aJ7WYz)ni+2&N ze#TSM%3iLbGHWcJ2TNT=4|_oA0yi;p(ij}JTe^!qJ4Tao?6A8Cx)6+8e}ISBoHvS; zU-CSJVd+SmO~O4zlR_Nzf3DF%IHeB9b3xY*Vo)H!F4Goc7r1EN+DZhL|~vc^Lr1=yqbO9RiDO-cIOE0~oD$5*zjd#x-^l zx3dAsD{(q_4{)gKD2_BhI%gsrL{T%qN__{huMwdCe60wq#GGZH?8Ui!KxKuUD4Goz z`Nmd6Jb?>o3oK7fu@DtqVEM>cOOezM-j`NdivE2dxJR^=@b*RtqC2(`&5co% zv>m{CVCXC<_RI$Wu z!0lcKvF9L8t>2yQAa?us;J~(~gSefJQ{vLG9Ynx*oB-E3br7VF)16+0r)azz$BpY} zJjM9{?DMbYd5XKQ9P!OiXHPLWMvE^3-gyYkC_Drv#e0aTmNxiCXPk!^nAZl?GV~CE ze^`=|bmx=D8V~{D{D>Zf(f4H~CiT#M1IAPinXVd|1qE4gcXyS5L(Wb5u z-dIJrihA`8(ci6H#m(kT@I!6~@e<0Z5l-XYE+V~m1GLEb_M*X026%6Rr}yK3;$>Ft z8_uHp!#a2b9q25UyVOSguD27%BWmJHqn_=A*L{7IKgmgK>92?X{Nd>&j$hK?vcKUd zy8eV$MGPzY*29m3+`-v96fmc|lQ7u`7nX;egmS$;E{0a^gp*N29I$_BCyGK4k8No? z(cxTUeCZJAEKXWC#kU6goyCBS2;Qb%dojKV(yk_M*hL1?;qT5#y4O z`}S}bQ9BH3yg2V7Dw;!|W6fQK?@cot!b4p}w~ZEvC371c5aKyth<|t zuz=vjcz<`a9!g-C>Lymav*))+?n3(*kLY>AT}&x(!pJOlaWe}QY!T-!?q{H;b@ScD z`x|bgY^>)YCS-WvhY;L6#Pv)(6dV}tAtvALh-+z%hZtFcCNYWjKwG12-W>N3%isCo z<@_}d@vH_~E3L#sR5tF47X)uT#7493xD;!7iZ_k{_-ePYr*QW{XNETM6dgkVCF{LJ zplkpCd+T>Y>u)Qw5N*PHlICI!OA)gJp03(iie(!RM8gr5B5NJCmDo*|V)j;Vyqzkt z6!VXwoBxA5gh@7@F&=KhE2svLAf;v-@nJC3S>xA69Qp-%xy@}OiVoY7^2gt8MCL=h z$#|-?73S7Z*{DZbF(eeaSFUL*65>&boZPlzR~2g0Pirk&4nnnN&9)Xh521c5u33xl zX01?lyn{SFA2r@O-$uB+Le-OVZA8js^uaQ3ThZq^I^%7$tq^n2D|U*V$ZmxGzBt}a zL?1*yxm>ps(+8r%w4Lll8$C4o-}~)_(J6FcVr#ANoP)l^k4K0D0-ymr7>3@Bx@9kB z>_j)`_q7)h&C%cOuG)#1XnlwfXeYKh;u;9QVk`7hYvB&s$5wQmf$QY6yqVIMz z@z&QC!o4Rw0Hxt^KeX;dTG85N2RCntC0Kamv$p8QV diff --git a/莱洛三角切割/wheel.dxf b/莱洛三角切割/wheel.dxf deleted file mode 100644 index 919d8a8..0000000 --- a/莱洛三角切割/wheel.dxf +++ /dev/null @@ -1,9628 +0,0 @@ -999 -dxflib 3.17.0.0 - 0 -SECTION - 2 -HEADER - 9 -$ACADVER - 1 -AC1015 - 9 -$HANDSEED - 5 -FFFF - 9 -$INSUNITS - 70 -4 - 9 -$DIMEXE - 40 -1.25 - 9 -$TEXTSTYLE - 7 -Standard - 9 -$LIMMIN - 10 -0.0 - 20 -0.0 - 0 -ENDSEC - 0 -SECTION - 2 -TABLES - 0 -TABLE - 2 -VPORT - 5 -8 -100 -AcDbSymbolTable - 70 -1 - 0 -VPORT - 5 -30 -100 -AcDbSymbolTableRecord -100 -AcDbViewportTableRecord - 2 -*Active - 70 -0 - 10 -0.0 - 20 -0.0 - 11 -1.0 - 21 -1.0 - 12 -286.30555555555549 - 22 -148.5 - 13 -0.0 - 23 -0.0 - 14 -10.0 - 24 -10.0 - 15 -10.0 - 25 -10.0 - 16 -0.0 - 26 -0.0 - 36 -1.0 - 17 -0.0 - 27 -0.0 - 37 -0.0 - 40 -297.0 - 41 -1.92798353909465 - 42 -50.0 - 43 -0.0 - 44 -0.0 - 50 -0.0 - 51 -0.0 - 71 -0 - 72 -100 - 73 -1 - 74 -3 - 75 -1 - 76 -1 - 77 -0 - 78 -0 -281 -0 - 65 -1 -110 -0.0 -120 -0.0 -130 -0.0 -111 -1.0 -121 -0.0 -131 -0.0 -112 -0.0 -122 -1.0 -132 -0.0 - 79 -0 -146 -0.0 - 0 -ENDTAB - 0 -TABLE - 2 -LTYPE - 5 -5 -100 -AcDbSymbolTable - 70 -25 - 0 -LTYPE - 5 -14 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BYBLOCK - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -15 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BYLAYER - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -16 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -CONTINUOUS - 70 -0 - 3 -Solid line - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -31 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -ACAD_ISO02W100 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -32 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -ACAD_ISO03W100 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -33 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -ACAD_ISO04W100 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -34 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -ACAD_ISO05W100 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -35 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BORDER - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -36 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BORDER2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -37 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -BORDERX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -38 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -CENTER - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -39 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -CENTER2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3A -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -CENTERX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3B -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHDOT - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3C -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHDOT2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3D -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHDOTX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3E -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHED - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -3F -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHED2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -40 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DASHEDX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -41 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DIVIDE - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -42 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DIVIDE2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -43 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DIVIDEX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -44 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DOT - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -45 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DOT2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -LTYPE - 5 -46 -100 -AcDbSymbolTableRecord -100 -AcDbLinetypeTableRecord - 2 -DOTX2 - 70 -0 - 3 - - 72 -65 - 73 -0 - 40 -0.0 - 0 -ENDTAB - 0 -TABLE - 2 -LAYER - 5 -2 -100 -AcDbSymbolTable - 70 -1 - 0 -LAYER - 5 -10 -100 -AcDbSymbolTableRecord -100 -AcDbLayerTableRecord - 2 -0 - 70 -0 - 62 --1 -420 -0 - 6 -CONTINUOUS -370 -1 -390 -F - 0 -ENDTAB - 0 -STYLE - 5 -47 -100 -AcDbSymbolTableRecord -100 -AcDbTextStyleTableRecord - 2 - - 70 -0 - 40 -0.0 - 41 -0.0 - 50 -0.0 - 71 -0 - 42 -0.0 - 3 - - 4 - -1001 -ACAD -1000 - -1071 -0 - 0 -TABLE - 2 -VIEW - 5 -6 -100 -AcDbSymbolTable - 70 -0 - 0 -ENDTAB - 0 -TABLE - 2 -UCS - 5 -7 -100 -AcDbSymbolTable - 70 -0 - 0 -ENDTAB - 0 -TABLE - 2 -APPID - 5 -9 -100 -AcDbSymbolTable - 70 -1 - 0 -APPID - 5 -12 -100 -AcDbSymbolTableRecord -100 -AcDbRegAppTableRecord - 2 -ACAD - 70 -0 - 0 -ENDTAB - 0 -TABLE - 2 -DIMSTYLE - 5 -A -100 -AcDbSymbolTable - 70 -1 -100 -AcDbDimStyleTable - 71 -0 - 0 -DIMSTYLE -105 -27 -100 -AcDbSymbolTableRecord -100 -AcDbDimStyleTableRecord - 2 -Standard - 41 -1.0 - 42 -1.0 - 43 -3.75 - 44 -1.0 - 70 -0 - 73 -0 - 74 -0 - 77 -1 - 78 -8 -140 -1.0 -141 -2.5 -143 -0.03937007874016 -147 -1.0 -171 -3 -172 -1 -271 -2 -272 -2 -274 -3 -278 -44 -283 -0 -284 -8 -340 -20000000 - 0 -ENDTAB - 0 -TABLE - 2 -BLOCK_RECORD - 5 -1 -100 -AcDbSymbolTable - 70 -1 - 0 -BLOCK_RECORD - 5 -1F -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -*Model_Space -340 -22 - 0 -BLOCK_RECORD - 5 -1B -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -*Paper_Space -340 -1E - 0 -BLOCK_RECORD - 5 -23 -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -*Paper_Space0 -340 -26 - 0 -BLOCK_RECORD - 5 -48 -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -myblock1 -340 -0 - 0 -BLOCK_RECORD - 5 -49 -100 -AcDbSymbolTableRecord -100 -AcDbBlockTableRecord - 2 -myblock2 -340 -0 - 0 -ENDTAB - 0 -ENDSEC - 0 -SECTION - 2 -BLOCKS - 0 -BLOCK - 5 -20 -100 -AcDbEntity - 8 -0 -100 -AcDbBlockBegin - 2 -*Model_Space - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -*Model_Space - 1 - - 0 -ENDBLK - 5 -21 -100 -AcDbEntity - 8 -0 -100 -AcDbBlockEnd - 0 -BLOCK - 5 -1C -100 -AcDbEntity - 67 -1 - 8 -0 -100 -AcDbBlockBegin - 2 -*Paper_Space - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -*Paper_Space - 1 - - 0 -ENDBLK - 5 -1D -100 -AcDbEntity - 67 -1 - 8 -0 -100 -AcDbBlockEnd - 0 -BLOCK - 5 -24 -100 -AcDbEntity - 8 -0 -100 -AcDbBlockBegin - 2 -*Paper_Space0 - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -*Paper_Space0 - 1 - - 0 -ENDBLK - 5 -25 -100 -AcDbEntity - 8 -0 -100 -AcDbBlockEnd - 0 -BLOCK - 5 -4A -100 -AcDbEntity - 8 -0 -100 -AcDbBlockBegin - 2 -myblock1 - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -myblock1 - 1 - - 0 -ENDBLK - 5 -4B -100 -AcDbEntity - 8 -0 -100 -AcDbBlockEnd - 0 -BLOCK - 5 -4C -100 -AcDbEntity - 8 -0 -100 -AcDbBlockBegin - 2 -myblock2 - 70 -0 - 10 -0.0 - 20 -0.0 - 30 -0.0 - 3 -myblock2 - 1 - - 0 -ENDBLK - 5 -4D -100 -AcDbEntity - 8 -0 -100 -AcDbBlockEnd - 0 -ENDSEC - 0 -SECTION - 2 -ENTITIES - 0 -LWPOLYLINE - 5 -4E -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -129 - 70 -0 - 10 -200.00999450683594 - 20 -249.99998474121094 - 30 -0.0 - 10 -197.43748474121094 - 20 -249.93498229980469 - 30 -0.0 - 10 -194.89749145507812 - 20 -249.74249267578125 - 30 -0.0 - 10 -192.39498901367187 - 20 -249.42498779296875 - 30 -0.0 - 10 -189.9324951171875 - 20 -248.9849853515625 - 30 -0.0 - 10 -187.51498413085937 - 20 -248.42498779296875 - 30 -0.0 - 10 -185.13998413085937 - 20 -247.75248718261719 - 30 -0.0 - 10 -182.81748962402344 - 20 -246.96498107910156 - 30 -0.0 - 10 -180.5474853515625 - 20 -246.06999206542969 - 30 -0.0 - 10 -178.33248901367188 - 20 -245.06999206542969 - 30 -0.0 - 10 -176.177490234375 - 20 -243.96498107910156 - 30 -0.0 - 10 -174.08248901367188 - 20 -242.76248168945312 - 30 -0.0 - 10 -172.05499267578125 - 20 -241.45999145507812 - 30 -0.0 - 10 -170.09498596191406 - 20 -240.06748962402344 - 30 -0.0 - 10 -168.20498657226562 - 20 -238.58248901367187 - 30 -0.0 - 10 -166.38998413085937 - 20 -237.00999450683594 - 30 -0.0 - 10 -164.65498352050781 - 20 -235.35498046875 - 30 -0.0 - 10 -162.99998474121094 - 20 -233.61997985839844 - 30 -0.0 - 10 -161.427490234375 - 20 -231.80499267578125 - 30 -0.0 - 10 -159.94248962402344 - 20 -229.91499328613281 - 30 -0.0 - 10 -158.54998779296875 - 20 -227.95498657226562 - 30 -0.0 - 10 -157.24748229980469 - 20 -225.927490234375 - 30 -0.0 - 10 -156.04498291015625 - 20 -223.83248901367188 - 30 -0.0 - 10 -154.93998718261719 - 20 -221.677490234375 - 30 -0.0 - 10 -153.93998718261719 - 20 -219.46249389648437 - 30 -0.0 - 10 -153.04498291015625 - 20 -217.19248962402344 - 30 -0.0 - 10 -152.25749206542969 - 20 -214.8699951171875 - 30 -0.0 - 10 -151.58499145507812 - 20 -212.4949951171875 - 30 -0.0 - 10 -151.02499389648437 - 20 -210.07748413085937 - 30 -0.0 - 10 -150.58499145507812 - 20 -207.614990234375 - 30 -0.0 - 10 -150.26748657226562 - 20 -205.11248779296875 - 30 -0.0 - 10 -150.07498168945312 - 20 -202.57249450683594 - 30 -0.0 - 10 -150.00999450683594 - 20 -199.99998474121094 - 30 -0.0 - 10 -150.07498168945312 - 20 -197.427490234375 - 30 -0.0 - 10 -150.26748657226562 - 20 -194.88748168945312 - 30 -0.0 - 10 -150.58499145507812 - 20 -192.38499450683594 - 30 -0.0 - 10 -151.02499389648437 - 20 -189.9224853515625 - 30 -0.0 - 10 -151.58499145507812 - 20 -187.50498962402344 - 30 -0.0 - 10 -152.25749206542969 - 20 -185.12998962402344 - 30 -0.0 - 10 -153.04498291015625 - 20 -182.8074951171875 - 30 -0.0 - 10 -153.93998718261719 - 20 -180.53749084472656 - 30 -0.0 - 10 -154.93998718261719 - 20 -178.32249450683594 - 30 -0.0 - 10 -156.04498291015625 - 20 -176.16749572753906 - 30 -0.0 - 10 -157.24748229980469 - 20 -174.07249450683594 - 30 -0.0 - 10 -158.54998779296875 - 20 -172.04498291015625 - 30 -0.0 - 10 -159.94248962402344 - 20 -170.08499145507812 - 30 -0.0 - 10 -161.427490234375 - 20 -168.19499206542969 - 30 -0.0 - 10 -162.99998474121094 - 20 -166.37998962402344 - 30 -0.0 - 10 -164.65498352050781 - 20 -164.64498901367188 - 30 -0.0 - 10 -166.38998413085937 - 20 -162.989990234375 - 30 -0.0 - 10 -168.20498657226562 - 20 -161.41749572753906 - 30 -0.0 - 10 -170.09498596191406 - 20 -159.9324951171875 - 30 -0.0 - 10 -172.05499267578125 - 20 -158.53999328613281 - 30 -0.0 - 10 -174.08248901367188 - 20 -157.23748779296875 - 30 -0.0 - 10 -176.177490234375 - 20 -156.03498840332031 - 30 -0.0 - 10 -178.33248901367188 - 20 -154.92999267578125 - 30 -0.0 - 10 -180.5474853515625 - 20 -153.92999267578125 - 30 -0.0 - 10 -182.81748962402344 - 20 -153.03498840332031 - 30 -0.0 - 10 -185.13998413085937 - 20 -152.24748229980469 - 30 -0.0 - 10 -187.51498413085937 - 20 -151.57498168945312 - 30 -0.0 - 10 -189.9324951171875 - 20 -151.01498413085937 - 30 -0.0 - 10 -192.39498901367187 - 20 -150.57498168945312 - 30 -0.0 - 10 -194.89749145507812 - 20 -150.25749206542969 - 30 -0.0 - 10 -197.43748474121094 - 20 -150.06498718261719 - 30 -0.0 - 10 -200.00999450683594 - 20 -149.99998474121094 - 30 -0.0 - 10 -202.58248901367188 - 20 -150.06498718261719 - 30 -0.0 - 10 -205.12248229980469 - 20 -150.25749206542969 - 30 -0.0 - 10 -207.62498474121094 - 20 -150.57498168945312 - 30 -0.0 - 10 -210.08749389648437 - 20 -151.01498413085937 - 30 -0.0 - 10 -212.50498962402344 - 20 -151.57498168945312 - 30 -0.0 - 10 -214.87998962402344 - 20 -152.24748229980469 - 30 -0.0 - 10 -217.20248413085937 - 20 -153.03498840332031 - 30 -0.0 - 10 -219.47248840332031 - 20 -153.92999267578125 - 30 -0.0 - 10 -221.68748474121094 - 20 -154.92999267578125 - 30 -0.0 - 10 -223.84248352050781 - 20 -156.03498840332031 - 30 -0.0 - 10 -225.93748474121094 - 20 -157.23748779296875 - 30 -0.0 - 10 -227.96498107910156 - 20 -158.53999328613281 - 30 -0.0 - 10 -229.92498779296875 - 20 -159.9324951171875 - 30 -0.0 - 10 -231.81498718261719 - 20 -161.41749572753906 - 30 -0.0 - 10 -233.62998962402344 - 20 -162.989990234375 - 30 -0.0 - 10 -235.364990234375 - 20 -164.64498901367188 - 30 -0.0 - 10 -237.01998901367187 - 20 -166.37998962402344 - 30 -0.0 - 10 -238.59248352050781 - 20 -168.19499206542969 - 30 -0.0 - 10 -240.07748413085937 - 20 -170.08499145507812 - 30 -0.0 - 10 -241.46998596191406 - 20 -172.04498291015625 - 30 -0.0 - 10 -242.77249145507812 - 20 -174.07249450683594 - 30 -0.0 - 10 -243.97499084472656 - 20 -176.16749572753906 - 30 -0.0 - 10 -245.07998657226562 - 20 -178.32249450683594 - 30 -0.0 - 10 -246.07998657226562 - 20 -180.53749084472656 - 30 -0.0 - 10 -246.97499084472656 - 20 -182.8074951171875 - 30 -0.0 - 10 -247.76248168945313 - 20 -185.12998962402344 - 30 -0.0 - 10 -248.43498229980469 - 20 -187.50498962402344 - 30 -0.0 - 10 -248.99497985839844 - 20 -189.9224853515625 - 30 -0.0 - 10 -249.43498229980469 - 20 -192.38499450683594 - 30 -0.0 - 10 -249.75248718261719 - 20 -194.88748168945312 - 30 -0.0 - 10 -249.94499206542969 - 20 -197.427490234375 - 30 -0.0 - 10 -250.00997924804687 - 20 -199.99998474121094 - 30 -0.0 - 10 -249.94499206542969 - 20 -202.57249450683594 - 30 -0.0 - 10 -249.75248718261719 - 20 -205.11248779296875 - 30 -0.0 - 10 -249.43498229980469 - 20 -207.614990234375 - 30 -0.0 - 10 -248.99497985839844 - 20 -210.07748413085937 - 30 -0.0 - 10 -248.43498229980469 - 20 -212.4949951171875 - 30 -0.0 - 10 -247.76248168945313 - 20 -214.8699951171875 - 30 -0.0 - 10 -246.97499084472656 - 20 -217.19248962402344 - 30 -0.0 - 10 -246.07998657226562 - 20 -219.46249389648437 - 30 -0.0 - 10 -245.07998657226562 - 20 -221.677490234375 - 30 -0.0 - 10 -243.97499084472656 - 20 -223.83248901367188 - 30 -0.0 - 10 -242.77249145507812 - 20 -225.927490234375 - 30 -0.0 - 10 -241.46998596191406 - 20 -227.95498657226562 - 30 -0.0 - 10 -240.07748413085937 - 20 -229.91499328613281 - 30 -0.0 - 10 -238.59248352050781 - 20 -231.80499267578125 - 30 -0.0 - 10 -237.01998901367187 - 20 -233.61997985839844 - 30 -0.0 - 10 -235.364990234375 - 20 -235.35498046875 - 30 -0.0 - 10 -233.62998962402344 - 20 -237.00999450683594 - 30 -0.0 - 10 -231.81498718261719 - 20 -238.58248901367187 - 30 -0.0 - 10 -229.92498779296875 - 20 -240.06748962402344 - 30 -0.0 - 10 -227.96498107910156 - 20 -241.45999145507812 - 30 -0.0 - 10 -225.93748474121094 - 20 -242.76248168945312 - 30 -0.0 - 10 -223.84248352050781 - 20 -243.96498107910156 - 30 -0.0 - 10 -221.68748474121094 - 20 -245.06999206542969 - 30 -0.0 - 10 -219.47248840332031 - 20 -246.06999206542969 - 30 -0.0 - 10 -217.20248413085937 - 20 -246.96498107910156 - 30 -0.0 - 10 -214.87998962402344 - 20 -247.75248718261719 - 30 -0.0 - 10 -212.50498962402344 - 20 -248.42498779296875 - 30 -0.0 - 10 -210.08749389648437 - 20 -248.9849853515625 - 30 -0.0 - 10 -207.62498474121094 - 20 -249.42498779296875 - 30 -0.0 - 10 -205.12248229980469 - 20 -249.74249267578125 - 30 -0.0 - 10 -202.58248901367188 - 20 -249.93498229980469 - 30 -0.0 - 10 -200.00999450683594 - 20 -249.99998474121094 - 30 -0.0 - 0 -LWPOLYLINE - 5 -4F -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -33 - 70 -0 - 10 -203.15748596191406 - 20 -206.14999389648437 - 30 -0.0 - 10 -202.97499084472656 - 20 -206.13249206542969 - 30 -0.0 - 10 -202.8074951171875 - 20 -206.07998657226562 - 30 -0.0 - 10 -202.65498352050781 - 20 -205.99748229980469 - 30 -0.0 - 10 -202.51998901367187 - 20 -205.88748168945312 - 30 -0.0 - 10 -202.40998840332031 - 20 -205.75248718261719 - 30 -0.0 - 10 -202.32748413085937 - 20 -205.59999084472656 - 30 -0.0 - 10 -202.27499389648437 - 20 -205.4324951171875 - 30 -0.0 - 10 -202.25749206542969 - 20 -205.24998474121094 - 30 -0.0 - 10 -202.27499389648437 - 20 -205.06999206542969 - 30 -0.0 - 10 -202.32748413085937 - 20 -204.89999389648437 - 30 -0.0 - 10 -202.40998840332031 - 20 -204.74748229980469 - 30 -0.0 - 10 -202.51998901367187 - 20 -204.614990234375 - 30 -0.0 - 10 -202.65498352050781 - 20 -204.50498962402344 - 30 -0.0 - 10 -202.8074951171875 - 20 -204.4224853515625 - 30 -0.0 - 10 -202.97499084472656 - 20 -204.3699951171875 - 30 -0.0 - 10 -203.15748596191406 - 20 -204.35249328613281 - 30 -0.0 - 10 -203.33998107910156 - 20 -204.3699951171875 - 30 -0.0 - 10 -203.50749206542969 - 20 -204.4224853515625 - 30 -0.0 - 10 -203.65998840332031 - 20 -204.50498962402344 - 30 -0.0 - 10 -203.79498291015625 - 20 -204.614990234375 - 30 -0.0 - 10 -203.90498352050781 - 20 -204.74748229980469 - 30 -0.0 - 10 -203.98748779296875 - 20 -204.89999389648437 - 30 -0.0 - 10 -204.03999328613281 - 20 -205.06999206542969 - 30 -0.0 - 10 -204.0574951171875 - 20 -205.24998474121094 - 30 -0.0 - 10 -204.03999328613281 - 20 -205.4324951171875 - 30 -0.0 - 10 -203.98748779296875 - 20 -205.59999084472656 - 30 -0.0 - 10 -203.90498352050781 - 20 -205.75248718261719 - 30 -0.0 - 10 -203.79498291015625 - 20 -205.88748168945312 - 30 -0.0 - 10 -203.65998840332031 - 20 -205.99748229980469 - 30 -0.0 - 10 -203.50749206542969 - 20 -206.07998657226562 - 30 -0.0 - 10 -203.33998107910156 - 20 -206.13249206542969 - 30 -0.0 - 10 -203.15748596191406 - 20 -206.14999389648437 - 30 -0.0 - 0 -LWPOLYLINE - 5 -50 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -33 - 70 -0 - 10 -196.8599853515625 - 20 -206.14999389648437 - 30 -0.0 - 10 -196.677490234375 - 20 -206.13249206542969 - 30 -0.0 - 10 -196.50999450683594 - 20 -206.07998657226562 - 30 -0.0 - 10 -196.35748291015625 - 20 -205.99748229980469 - 30 -0.0 - 10 -196.22248840332031 - 20 -205.88748168945312 - 30 -0.0 - 10 -196.11248779296875 - 20 -205.75248718261719 - 30 -0.0 - 10 -196.02998352050781 - 20 -205.59999084472656 - 30 -0.0 - 10 -195.97749328613281 - 20 -205.4324951171875 - 30 -0.0 - 10 -195.95999145507812 - 20 -205.24998474121094 - 30 -0.0 - 10 -195.97749328613281 - 20 -205.06999206542969 - 30 -0.0 - 10 -196.02998352050781 - 20 -204.89999389648437 - 30 -0.0 - 10 -196.11248779296875 - 20 -204.74748229980469 - 30 -0.0 - 10 -196.22248840332031 - 20 -204.614990234375 - 30 -0.0 - 10 -196.35748291015625 - 20 -204.50498962402344 - 30 -0.0 - 10 -196.50999450683594 - 20 -204.4224853515625 - 30 -0.0 - 10 -196.677490234375 - 20 -204.3699951171875 - 30 -0.0 - 10 -196.8599853515625 - 20 -204.35249328613281 - 30 -0.0 - 10 -197.04248046875 - 20 -204.3699951171875 - 30 -0.0 - 10 -197.20999145507812 - 20 -204.4224853515625 - 30 -0.0 - 10 -197.36248779296875 - 20 -204.50498962402344 - 30 -0.0 - 10 -197.49748229980469 - 20 -204.614990234375 - 30 -0.0 - 10 -197.60748291015625 - 20 -204.74748229980469 - 30 -0.0 - 10 -197.68998718261719 - 20 -204.89999389648437 - 30 -0.0 - 10 -197.74249267578125 - 20 -205.06999206542969 - 30 -0.0 - 10 -197.75999450683594 - 20 -205.24998474121094 - 30 -0.0 - 10 -197.74249267578125 - 20 -205.4324951171875 - 30 -0.0 - 10 -197.68998718261719 - 20 -205.59999084472656 - 30 -0.0 - 10 -197.60748291015625 - 20 -205.75248718261719 - 30 -0.0 - 10 -197.49748229980469 - 20 -205.88748168945312 - 30 -0.0 - 10 -197.36248779296875 - 20 -205.99748229980469 - 30 -0.0 - 10 -197.20999145507812 - 20 -206.07998657226562 - 30 -0.0 - 10 -197.04248046875 - 20 -206.13249206542969 - 30 -0.0 - 10 -196.8599853515625 - 20 -206.14999389648437 - 30 -0.0 - 0 -LWPOLYLINE - 5 -51 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -33 - 70 -0 - 10 -203.15998840332031 - 20 -195.64749145507812 - 30 -0.0 - 10 -202.97749328613281 - 20 -195.62998962402344 - 30 -0.0 - 10 -202.80998229980469 - 20 -195.57748413085937 - 30 -0.0 - 10 -202.65748596191406 - 20 -195.4949951171875 - 30 -0.0 - 10 -202.52249145507812 - 20 -195.38499450683594 - 30 -0.0 - 10 -202.41249084472656 - 20 -195.25248718261719 - 30 -0.0 - 10 -202.32998657226562 - 20 -195.09999084472656 - 30 -0.0 - 10 -202.27748107910156 - 20 -194.92999267578125 - 30 -0.0 - 10 -202.25999450683594 - 20 -194.74998474121094 - 30 -0.0 - 10 -202.27748107910156 - 20 -194.56748962402344 - 30 -0.0 - 10 -202.32998657226562 - 20 -194.39999389648437 - 30 -0.0 - 10 -202.41249084472656 - 20 -194.24748229980469 - 30 -0.0 - 10 -202.52249145507812 - 20 -194.11248779296875 - 30 -0.0 - 10 -202.65748596191406 - 20 -194.00248718261719 - 30 -0.0 - 10 -202.80998229980469 - 20 -193.91998291015625 - 30 -0.0 - 10 -202.97749328613281 - 20 -193.86749267578125 - 30 -0.0 - 10 -203.15998840332031 - 20 -193.84999084472656 - 30 -0.0 - 10 -203.34248352050781 - 20 -193.86749267578125 - 30 -0.0 - 10 -203.50999450683594 - 20 -193.91998291015625 - 30 -0.0 - 10 -203.66499328613281 - 20 -194.00248718261719 - 30 -0.0 - 10 -203.7974853515625 - 20 -194.11248779296875 - 30 -0.0 - 10 -203.90748596191406 - 20 -194.24748229980469 - 30 -0.0 - 10 -203.99249267578125 - 20 -194.39999389648437 - 30 -0.0 - 10 -204.04498291015625 - 20 -194.56748962402344 - 30 -0.0 - 10 -204.06248474121094 - 20 -194.74998474121094 - 30 -0.0 - 10 -204.04498291015625 - 20 -194.92999267578125 - 30 -0.0 - 10 -203.99249267578125 - 20 -195.09999084472656 - 30 -0.0 - 10 -203.90748596191406 - 20 -195.25248718261719 - 30 -0.0 - 10 -203.7974853515625 - 20 -195.38499450683594 - 30 -0.0 - 10 -203.66499328613281 - 20 -195.4949951171875 - 30 -0.0 - 10 -203.50999450683594 - 20 -195.57748413085937 - 30 -0.0 - 10 -203.34248352050781 - 20 -195.62998962402344 - 30 -0.0 - 10 -203.15998840332031 - 20 -195.64749145507812 - 30 -0.0 - 0 -LWPOLYLINE - 5 -52 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -33 - 70 -0 - 10 -196.86248779296875 - 20 -195.64999389648437 - 30 -0.0 - 10 -196.67999267578125 - 20 -195.63249206542969 - 30 -0.0 - 10 -196.51248168945313 - 20 -195.57998657226562 - 30 -0.0 - 10 -196.3599853515625 - 20 -195.49748229980469 - 30 -0.0 - 10 -196.22499084472656 - 20 -195.38748168945312 - 30 -0.0 - 10 -196.114990234375 - 20 -195.25498962402344 - 30 -0.0 - 10 -196.03248596191406 - 20 -195.10249328613281 - 30 -0.0 - 10 -195.97998046875 - 20 -194.9324951171875 - 30 -0.0 - 10 -195.96249389648437 - 20 -194.75248718261719 - 30 -0.0 - 10 -195.97998046875 - 20 -194.56999206542969 - 30 -0.0 - 10 -196.03248596191406 - 20 -194.40248107910156 - 30 -0.0 - 10 -196.114990234375 - 20 -194.24998474121094 - 30 -0.0 - 10 -196.22499084472656 - 20 -194.114990234375 - 30 -0.0 - 10 -196.3599853515625 - 20 -194.00498962402344 - 30 -0.0 - 10 -196.51248168945313 - 20 -193.9224853515625 - 30 -0.0 - 10 -196.67999267578125 - 20 -193.8699951171875 - 30 -0.0 - 10 -196.86248779296875 - 20 -193.85249328613281 - 30 -0.0 - 10 -197.04498291015625 - 20 -193.8699951171875 - 30 -0.0 - 10 -197.21249389648437 - 20 -193.9224853515625 - 30 -0.0 - 10 -197.364990234375 - 20 -194.00498962402344 - 30 -0.0 - 10 -197.49998474121094 - 20 -194.114990234375 - 30 -0.0 - 10 -197.6099853515625 - 20 -194.24998474121094 - 30 -0.0 - 10 -197.69248962402344 - 20 -194.40248107910156 - 30 -0.0 - 10 -197.7449951171875 - 20 -194.56999206542969 - 30 -0.0 - 10 -197.76248168945312 - 20 -194.75248718261719 - 30 -0.0 - 10 -197.7449951171875 - 20 -194.9324951171875 - 30 -0.0 - 10 -197.69248962402344 - 20 -195.10249328613281 - 30 -0.0 - 10 -197.6099853515625 - 20 -195.25498962402344 - 30 -0.0 - 10 -197.49998474121094 - 20 -195.38748168945312 - 30 -0.0 - 10 -197.364990234375 - 20 -195.49748229980469 - 30 -0.0 - 10 -197.21249389648437 - 20 -195.57998657226562 - 30 -0.0 - 10 -197.04498291015625 - 20 -195.63249206542969 - 30 -0.0 - 10 -196.86248779296875 - 20 -195.64999389648437 - 30 -0.0 - 0 -LWPOLYLINE - 5 -53 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -65 - 70 -0 - 10 -200.01248168945312 - 20 -203.49998474121094 - 30 -0.0 - 10 -199.65498352050781 - 20 -203.48248291015625 - 30 -0.0 - 10 -199.3074951171875 - 20 -203.42999267578125 - 30 -0.0 - 10 -198.96998596191406 - 20 -203.34248352050781 - 30 -0.0 - 10 -198.64999389648437 - 20 -203.22499084472656 - 30 -0.0 - 10 -198.34248352050781 - 20 -203.07748413085937 - 30 -0.0 - 10 -198.05499267578125 - 20 -202.90248107910156 - 30 -0.0 - 10 -197.78498840332031 - 20 -202.69998168945312 - 30 -0.0 - 10 -197.53498840332031 - 20 -202.47499084472656 - 30 -0.0 - 10 -197.30998229980469 - 20 -202.22499084472656 - 30 -0.0 - 10 -197.10748291015625 - 20 -201.95748901367187 - 30 -0.0 - 10 -196.9324951171875 - 20 -201.66748046875 - 30 -0.0 - 10 -196.78498840332031 - 20 -201.36248779296875 - 30 -0.0 - 10 -196.66748046875 - 20 -201.03999328613281 - 30 -0.0 - 10 -196.57998657226562 - 20 -200.70498657226562 - 30 -0.0 - 10 -196.52748107910156 - 20 -200.35748291015625 - 30 -0.0 - 10 -196.50999450683594 - 20 -199.99998474121094 - 30 -0.0 - 10 -196.52748107910156 - 20 -199.64248657226562 - 30 -0.0 - 10 -196.57998657226562 - 20 -199.29498291015625 - 30 -0.0 - 10 -196.66748046875 - 20 -198.95999145507812 - 30 -0.0 - 10 -196.78498840332031 - 20 -198.63748168945312 - 30 -0.0 - 10 -196.9324951171875 - 20 -198.33248901367188 - 30 -0.0 - 10 -197.10748291015625 - 20 -198.04248046875 - 30 -0.0 - 10 -197.30998229980469 - 20 -197.77499389648437 - 30 -0.0 - 10 -197.53498840332031 - 20 -197.52499389648437 - 30 -0.0 - 10 -197.78498840332031 - 20 -197.29998779296875 - 30 -0.0 - 10 -198.05499267578125 - 20 -197.09748840332031 - 30 -0.0 - 10 -198.34248352050781 - 20 -196.9224853515625 - 30 -0.0 - 10 -198.64999389648437 - 20 -196.77499389648437 - 30 -0.0 - 10 -198.96998596191406 - 20 -196.65748596191406 - 30 -0.0 - 10 -199.3074951171875 - 20 -196.56999206542969 - 30 -0.0 - 10 -199.65498352050781 - 20 -196.51748657226562 - 30 -0.0 - 10 -200.01248168945312 - 20 -196.49998474121094 - 30 -0.0 - 10 -200.3699951171875 - 20 -196.51748657226562 - 30 -0.0 - 10 -200.71748352050781 - 20 -196.56999206542969 - 30 -0.0 - 10 -201.052490234375 - 20 -196.65748596191406 - 30 -0.0 - 10 -201.37498474121094 - 20 -196.77499389648437 - 30 -0.0 - 10 -201.67999267578125 - 20 -196.9224853515625 - 30 -0.0 - 10 -201.96998596191406 - 20 -197.09748840332031 - 30 -0.0 - 10 -202.23748779296875 - 20 -197.29998779296875 - 30 -0.0 - 10 -202.48748779296875 - 20 -197.52499389648437 - 30 -0.0 - 10 -202.71249389648437 - 20 -197.77499389648437 - 30 -0.0 - 10 -202.91499328613281 - 20 -198.04248046875 - 30 -0.0 - 10 -203.08998107910156 - 20 -198.33248901367188 - 30 -0.0 - 10 -203.23748779296875 - 20 -198.63748168945312 - 30 -0.0 - 10 -203.35498046875 - 20 -198.95999145507812 - 30 -0.0 - 10 -203.44248962402344 - 20 -199.29498291015625 - 30 -0.0 - 10 -203.4949951171875 - 20 -199.64248657226562 - 30 -0.0 - 10 -203.51248168945312 - 20 -199.99998474121094 - 30 -0.0 - 10 -203.4949951171875 - 20 -200.35748291015625 - 30 -0.0 - 10 -203.44248962402344 - 20 -200.70498657226562 - 30 -0.0 - 10 -203.35498046875 - 20 -201.03999328613281 - 30 -0.0 - 10 -203.23748779296875 - 20 -201.36248779296875 - 30 -0.0 - 10 -203.08998107910156 - 20 -201.66748046875 - 30 -0.0 - 10 -202.91499328613281 - 20 -201.95748901367187 - 30 -0.0 - 10 -202.71249389648437 - 20 -202.22499084472656 - 30 -0.0 - 10 -202.48748779296875 - 20 -202.47499084472656 - 30 -0.0 - 10 -202.23748779296875 - 20 -202.69998168945312 - 30 -0.0 - 10 -201.96998596191406 - 20 -202.90248107910156 - 30 -0.0 - 10 -201.67999267578125 - 20 -203.07748413085937 - 30 -0.0 - 10 -201.37498474121094 - 20 -203.22499084472656 - 30 -0.0 - 10 -201.052490234375 - 20 -203.34248352050781 - 30 -0.0 - 10 -200.71748352050781 - 20 -203.42999267578125 - 30 -0.0 - 10 -200.3699951171875 - 20 -203.48248291015625 - 30 -0.0 - 10 -200.01248168945312 - 20 -203.49998474121094 - 30 -0.0 - 0 -LWPOLYLINE - 5 -54 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -49 - 70 -0 - 10 -198.25999450683594 - 20 -243.24998474121094 - 30 -0.0 - 10 -198.26998901367187 - 20 -243.07249450683594 - 30 -0.0 - 10 -198.29498291015625 - 20 -242.89749145507812 - 30 -0.0 - 10 -198.33749389648437 - 20 -242.72998046875 - 30 -0.0 - 10 -198.39749145507812 - 20 -242.56999206542969 - 30 -0.0 - 10 -198.5574951171875 - 20 -242.27249145507812 - 30 -0.0 - 10 -198.77249145507812 - 20 -242.01248168945313 - 30 -0.0 - 10 -199.02998352050781 - 20 -241.79998779296875 - 30 -0.0 - 10 -199.32748413085937 - 20 -241.63748168945312 - 30 -0.0 - 10 -199.489990234375 - 20 -241.57998657226562 - 30 -0.0 - 10 -199.65748596191406 - 20 -241.53498840332031 - 30 -0.0 - 10 -199.82998657226562 - 20 -241.50999450683594 - 30 -0.0 - 10 -200.00999450683594 - 20 -241.49998474121094 - 30 -0.0 - 10 -200.18748474121094 - 20 -241.50999450683594 - 30 -0.0 - 10 -200.36248779296875 - 20 -241.53498840332031 - 30 -0.0 - 10 -200.52998352050781 - 20 -241.57998657226562 - 30 -0.0 - 10 -200.68998718261719 - 20 -241.63748168945312 - 30 -0.0 - 10 -200.98748779296875 - 20 -241.79998779296875 - 30 -0.0 - 10 -201.24748229980469 - 20 -242.01248168945313 - 30 -0.0 - 10 -201.45999145507812 - 20 -242.27249145507812 - 30 -0.0 - 10 -201.62248229980469 - 20 -242.56999206542969 - 30 -0.0 - 10 -201.67999267578125 - 20 -242.72998046875 - 30 -0.0 - 10 -201.72499084472656 - 20 -242.89749145507812 - 30 -0.0 - 10 -201.74998474121094 - 20 -243.07249450683594 - 30 -0.0 - 10 -201.75999450683594 - 20 -243.24998474121094 - 30 -0.0 - 10 -201.74998474121094 - 20 -243.42999267578125 - 30 -0.0 - 10 -201.72499084472656 - 20 -243.60249328613281 - 30 -0.0 - 10 -201.67999267578125 - 20 -243.76998901367187 - 30 -0.0 - 10 -201.62248229980469 - 20 -243.93247985839844 - 30 -0.0 - 10 -201.45999145507812 - 20 -244.22998046875 - 30 -0.0 - 10 -201.24748229980469 - 20 -244.48748779296875 - 30 -0.0 - 10 -200.98748779296875 - 20 -244.70248413085937 - 30 -0.0 - 10 -200.68998718261719 - 20 -244.86248779296875 - 30 -0.0 - 10 -200.52998352050781 - 20 -244.9224853515625 - 30 -0.0 - 10 -200.36248779296875 - 20 -244.96498107910156 - 30 -0.0 - 10 -200.18748474121094 - 20 -244.989990234375 - 30 -0.0 - 10 -200.00999450683594 - 20 -244.99998474121094 - 30 -0.0 - 10 -199.82998657226562 - 20 -244.989990234375 - 30 -0.0 - 10 -199.65748596191406 - 20 -244.96498107910156 - 30 -0.0 - 10 -199.489990234375 - 20 -244.9224853515625 - 30 -0.0 - 10 -199.32748413085937 - 20 -244.86248779296875 - 30 -0.0 - 10 -199.02998352050781 - 20 -244.70248413085937 - 30 -0.0 - 10 -198.77249145507812 - 20 -244.48748779296875 - 30 -0.0 - 10 -198.5574951171875 - 20 -244.22998046875 - 30 -0.0 - 10 -198.39749145507812 - 20 -243.93247985839844 - 30 -0.0 - 10 -198.33749389648437 - 20 -243.76998901367187 - 30 -0.0 - 10 -198.29498291015625 - 20 -243.60249328613281 - 30 -0.0 - 10 -198.26998901367187 - 20 -243.42999267578125 - 30 -0.0 - 10 -198.25999450683594 - 20 -243.24998474121094 - 30 -0.0 - 0 -LWPOLYLINE - 5 -55 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -53 - 70 -0 - 10 -176.864990234375 - 20 -236.57998657226562 - 30 -0.0 - 10 -177.07249450683594 - 20 -236.29248046875 - 30 -0.0 - 10 -177.32498168945313 - 20 -236.05998229980469 - 30 -0.0 - 10 -177.614990234375 - 20 -235.88249206542969 - 30 -0.0 - 10 -177.76998901367188 - 20 -235.81748962402344 - 30 -0.0 - 10 -177.92999267578125 - 20 -235.76498413085937 - 30 -0.0 - 10 -178.09248352050781 - 20 -235.72998046875 - 30 -0.0 - 10 -178.25999450683594 - 20 -235.70999145507812 - 30 -0.0 - 10 -178.42999267578125 - 20 -235.70748901367187 - 30 -0.0 - 10 -178.59748840332031 - 20 -235.71998596191406 - 30 -0.0 - 10 -178.76748657226562 - 20 -235.74748229980469 - 30 -0.0 - 10 -178.93498229980469 - 20 -235.79498291015625 - 30 -0.0 - 10 -179.09748840332031 - 20 -235.85748291015625 - 30 -0.0 - 10 -179.25749206542969 - 20 -235.93998718261719 - 30 -0.0 - 10 -179.54498291015625 - 20 -236.14749145507812 - 30 -0.0 - 10 -179.77748107910156 - 20 -236.39999389648437 - 30 -0.0 - 10 -179.95498657226562 - 20 -236.68998718261719 - 30 -0.0 - 10 -180.02249145507812 - 20 -236.84498596191406 - 30 -0.0 - 10 -180.07249450683594 - 20 -237.00498962402344 - 30 -0.0 - 10 -180.10748291015625 - 20 -237.16748046875 - 30 -0.0 - 10 -180.12748718261719 - 20 -237.33499145507812 - 30 -0.0 - 10 -180.13249206542969 - 20 -237.50498962402344 - 30 -0.0 - 10 -180.1199951171875 - 20 -237.6724853515625 - 30 -0.0 - 10 -180.08998107910156 - 20 -237.84248352050781 - 30 -0.0 - 10 -180.04249572753906 - 20 -238.00999450683594 - 30 -0.0 - 10 -179.97999572753906 - 20 -238.1724853515625 - 30 -0.0 - 10 -179.89749145507812 - 20 -238.33248901367187 - 30 -0.0 - 10 -179.68998718261719 - 20 -238.61997985839844 - 30 -0.0 - 10 -179.43748474121094 - 20 -238.85249328613281 - 30 -0.0 - 10 -179.14999389648437 - 20 -239.02998352050781 - 30 -0.0 - 10 -178.9949951171875 - 20 -239.09498596191406 - 30 -0.0 - 10 -178.83499145507812 - 20 -239.14749145507812 - 30 -0.0 - 10 -178.66998291015625 - 20 -239.18247985839844 - 30 -0.0 - 10 -178.50248718261719 - 20 -239.20248413085937 - 30 -0.0 - 10 -178.33499145507812 - 20 -239.20498657226562 - 30 -0.0 - 10 -178.16499328613281 - 20 -239.19248962402344 - 30 -0.0 - 10 -177.99748229980469 - 20 -239.16499328613281 - 30 -0.0 - 10 -177.82998657226562 - 20 -239.11749267578125 - 30 -0.0 - 10 -177.66749572753906 - 20 -239.05499267578125 - 30 -0.0 - 10 -177.50749206542969 - 20 -238.97248840332031 - 30 -0.0 - 10 -177.21998596191406 - 20 -238.76498413085937 - 30 -0.0 - 10 -176.9849853515625 - 20 -238.51248168945312 - 30 -0.0 - 10 -176.80998229980469 - 20 -238.22248840332031 - 30 -0.0 - 10 -176.74249267578125 - 20 -238.06748962402344 - 30 -0.0 - 10 -176.69248962402344 - 20 -237.90748596191406 - 30 -0.0 - 10 -176.65498352050781 - 20 -237.74497985839844 - 30 -0.0 - 10 -176.63499450683594 - 20 -237.57748413085937 - 30 -0.0 - 10 -176.63249206542969 - 20 -237.40748596191406 - 30 -0.0 - 10 -176.64498901367187 - 20 -237.239990234375 - 30 -0.0 - 10 -176.6724853515625 - 20 -237.06999206542969 - 30 -0.0 - 10 -176.71998596191406 - 20 -236.90248107910156 - 30 -0.0 - 10 -176.78248596191406 - 20 -236.739990234375 - 30 -0.0 - 10 -176.864990234375 - 20 -236.57998657226562 - 30 -0.0 - 0 -LWPOLYLINE - 5 -56 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -53 - 70 -0 - 10 -161.67498779296875 - 20 -220.10748291015625 - 30 -0.0 - 10 -161.83499145507812 - 20 -220.02499389648437 - 30 -0.0 - 10 -161.99748229980469 - 20 -219.96249389648437 - 30 -0.0 - 10 -162.16499328613281 - 20 -219.91499328613281 - 30 -0.0 - 10 -162.33499145507812 - 20 -219.88499450683594 - 30 -0.0 - 10 -162.50248718261719 - 20 -219.87248229980469 - 30 -0.0 - 10 -162.6724853515625 - 20 -219.87748718261719 - 30 -0.0 - 10 -162.83999633789062 - 20 -219.89749145507812 - 30 -0.0 - 10 -163.00248718261719 - 20 -219.93247985839844 - 30 -0.0 - 10 -163.16249084472656 - 20 -219.98248291015625 - 30 -0.0 - 10 -163.31748962402344 - 20 -220.04998779296875 - 30 -0.0 - 10 -163.60748291015625 - 20 -220.22749328613281 - 30 -0.0 - 10 -163.8599853515625 - 20 -220.45999145507812 - 30 -0.0 - 10 -164.06748962402344 - 20 -220.74748229980469 - 30 -0.0 - 10 -164.14999389648437 - 20 -220.90748596191406 - 30 -0.0 - 10 -164.21249389648437 - 20 -221.06999206542969 - 30 -0.0 - 10 -164.25999450683594 - 20 -221.23748779296875 - 30 -0.0 - 10 -164.28749084472656 - 20 -221.40748596191406 - 30 -0.0 - 10 -164.29998779296875 - 20 -221.57498168945312 - 30 -0.0 - 10 -164.2974853515625 - 20 -221.74497985839844 - 30 -0.0 - 10 -164.27748107910156 - 20 -221.91249084472656 - 30 -0.0 - 10 -164.24249267578125 - 20 -222.07498168945312 - 30 -0.0 - 10 -164.18998718261719 - 20 -222.2349853515625 - 30 -0.0 - 10 -164.12248229980469 - 20 -222.38998413085937 - 30 -0.0 - 10 -163.94749450683594 - 20 -222.67999267578125 - 30 -0.0 - 10 -163.71249389648437 - 20 -222.93247985839844 - 30 -0.0 - 10 -163.42498779296875 - 20 -223.13998413085937 - 30 -0.0 - 10 -163.26498413085937 - 20 -223.22248840332031 - 30 -0.0 - 10 -163.10249328613281 - 20 -223.28498840332031 - 30 -0.0 - 10 -162.93498229980469 - 20 -223.33248901367187 - 30 -0.0 - 10 -162.76748657226562 - 20 -223.3599853515625 - 30 -0.0 - 10 -162.59748840332031 - 20 -223.37248229980469 - 30 -0.0 - 10 -162.42999267578125 - 20 -223.36997985839844 - 30 -0.0 - 10 -162.26248168945312 - 20 -223.34999084472656 - 30 -0.0 - 10 -162.09748840332031 - 20 -223.31498718261719 - 30 -0.0 - 10 -161.93748474121094 - 20 -223.26248168945312 - 30 -0.0 - 10 -161.78248596191406 - 20 -223.19499206542969 - 30 -0.0 - 10 -161.4949951171875 - 20 -223.01998901367188 - 30 -0.0 - 10 -161.24249267578125 - 20 -222.78498840332031 - 30 -0.0 - 10 -161.03498840332031 - 20 -222.49748229980469 - 30 -0.0 - 10 -160.95248413085937 - 20 -222.33749389648437 - 30 -0.0 - 10 -160.88998413085937 - 20 -222.17498779296875 - 30 -0.0 - 10 -160.84248352050781 - 20 -222.00749206542969 - 30 -0.0 - 10 -160.81498718261719 - 20 -221.83749389648437 - 30 -0.0 - 10 -160.802490234375 - 20 -221.66998291015625 - 30 -0.0 - 10 -160.80499267578125 - 20 -221.49998474121094 - 30 -0.0 - 10 -160.82498168945312 - 20 -221.33248901367187 - 30 -0.0 - 10 -160.8599853515625 - 20 -221.16998291015625 - 30 -0.0 - 10 -160.91249084472656 - 20 -221.00999450683594 - 30 -0.0 - 10 -160.97749328613281 - 20 -220.85498046875 - 30 -0.0 - 10 -161.15498352050781 - 20 -220.56748962402344 - 30 -0.0 - 10 -161.38748168945312 - 20 -220.31498718261719 - 30 -0.0 - 10 -161.67498779296875 - 20 -220.10748291015625 - 30 -0.0 - 0 -LWPOLYLINE - 5 -57 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -49 - 70 -0 - 10 -156.75749206542969 - 20 -198.2449951171875 - 30 -0.0 - 10 -156.93748474121094 - 20 -198.25498962402344 - 30 -0.0 - 10 -157.1099853515625 - 20 -198.27998352050781 - 30 -0.0 - 10 -157.27749633789063 - 20 -198.32498168945312 - 30 -0.0 - 10 -157.43998718261719 - 20 -198.38249206542969 - 30 -0.0 - 10 -157.73748779296875 - 20 -198.54498291015625 - 30 -0.0 - 10 -157.9949951171875 - 20 -198.75749206542969 - 30 -0.0 - 10 -158.20999145507812 - 20 -199.01748657226562 - 30 -0.0 - 10 -158.3699951171875 - 20 -199.31498718261719 - 30 -0.0 - 10 -158.42999267578125 - 20 -199.47499084472656 - 30 -0.0 - 10 -158.47248840332031 - 20 -199.64248657226562 - 30 -0.0 - 10 -158.49748229980469 - 20 -199.81748962402344 - 30 -0.0 - 10 -158.50749206542969 - 20 -199.9949951171875 - 30 -0.0 - 10 -158.49748229980469 - 20 -200.17498779296875 - 30 -0.0 - 10 -158.47248840332031 - 20 -200.34748840332031 - 30 -0.0 - 10 -158.42999267578125 - 20 -200.51498413085937 - 30 -0.0 - 10 -158.3699951171875 - 20 -200.677490234375 - 30 -0.0 - 10 -158.20999145507812 - 20 -200.97499084472656 - 30 -0.0 - 10 -157.9949951171875 - 20 -201.23248291015625 - 30 -0.0 - 10 -157.73748779296875 - 20 -201.44749450683594 - 30 -0.0 - 10 -157.43998718261719 - 20 -201.60748291015625 - 30 -0.0 - 10 -157.27749633789063 - 20 -201.66748046875 - 30 -0.0 - 10 -157.1099853515625 - 20 -201.70999145507812 - 30 -0.0 - 10 -156.93748474121094 - 20 -201.7349853515625 - 30 -0.0 - 10 -156.75749206542969 - 20 -201.7449951171875 - 30 -0.0 - 10 -156.57998657226562 - 20 -201.7349853515625 - 30 -0.0 - 10 -156.40498352050781 - 20 -201.70999145507812 - 30 -0.0 - 10 -156.23748779296875 - 20 -201.66748046875 - 30 -0.0 - 10 -156.07748413085937 - 20 -201.60748291015625 - 30 -0.0 - 10 -155.77998352050781 - 20 -201.44749450683594 - 30 -0.0 - 10 -155.51998901367187 - 20 -201.23248291015625 - 30 -0.0 - 10 -155.3074951171875 - 20 -200.97499084472656 - 30 -0.0 - 10 -155.14498901367187 - 20 -200.677490234375 - 30 -0.0 - 10 -155.08749389648437 - 20 -200.51498413085937 - 30 -0.0 - 10 -155.04249572753906 - 20 -200.34748840332031 - 30 -0.0 - 10 -155.01748657226562 - 20 -200.17498779296875 - 30 -0.0 - 10 -155.00749206542969 - 20 -199.9949951171875 - 30 -0.0 - 10 -155.01748657226562 - 20 -199.81748962402344 - 30 -0.0 - 10 -155.04249572753906 - 20 -199.64248657226562 - 30 -0.0 - 10 -155.08749389648437 - 20 -199.47499084472656 - 30 -0.0 - 10 -155.14498901367187 - 20 -199.31498718261719 - 30 -0.0 - 10 -155.3074951171875 - 20 -199.01748657226562 - 30 -0.0 - 10 -155.51998901367187 - 20 -198.75749206542969 - 30 -0.0 - 10 -155.77998352050781 - 20 -198.54498291015625 - 30 -0.0 - 10 -156.07748413085937 - 20 -198.38249206542969 - 30 -0.0 - 10 -156.23748779296875 - 20 -198.32498168945312 - 30 -0.0 - 10 -156.40498352050781 - 20 -198.27998352050781 - 30 -0.0 - 10 -156.57998657226562 - 20 -198.25498962402344 - 30 -0.0 - 10 -156.75749206542969 - 20 -198.2449951171875 - 30 -0.0 - 0 -LWPOLYLINE - 5 -58 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -53 - 70 -0 - 10 -163.42999267578125 - 20 -176.85499572753906 - 30 -0.0 - 10 -163.71748352050781 - 20 -177.06248474121094 - 30 -0.0 - 10 -163.95248413085937 - 20 -177.31498718261719 - 30 -0.0 - 10 -164.12748718261719 - 20 -177.60249328613281 - 30 -0.0 - 10 -164.19499206542969 - 20 -177.75749206542969 - 30 -0.0 - 10 -164.24748229980469 - 20 -177.91749572753906 - 30 -0.0 - 10 -164.28248596191406 - 20 -178.07998657226562 - 30 -0.0 - 10 -164.302490234375 - 20 -178.24748229980469 - 30 -0.0 - 10 -164.30499267578125 - 20 -178.41749572753906 - 30 -0.0 - 10 -164.29249572753906 - 20 -178.58499145507812 - 30 -0.0 - 10 -164.26498413085937 - 20 -178.75498962402344 - 30 -0.0 - 10 -164.21748352050781 - 20 -178.9224853515625 - 30 -0.0 - 10 -164.15498352050781 - 20 -179.08499145507812 - 30 -0.0 - 10 -164.07249450683594 - 20 -179.2449951171875 - 30 -0.0 - 10 -163.864990234375 - 20 -179.53248596191406 - 30 -0.0 - 10 -163.61248779296875 - 20 -179.76498413085937 - 30 -0.0 - 10 -163.32249450683594 - 20 -179.94248962402344 - 30 -0.0 - 10 -163.16749572753906 - 20 -180.00999450683594 - 30 -0.0 - 10 -163.00749206542969 - 20 -180.05998229980469 - 30 -0.0 - 10 -162.84498596191406 - 20 -180.09498596191406 - 30 -0.0 - 10 -162.677490234375 - 20 -180.114990234375 - 30 -0.0 - 10 -162.50749206542969 - 20 -180.1199951171875 - 30 -0.0 - 10 -162.33999633789063 - 20 -180.10748291015625 - 30 -0.0 - 10 -162.16998291015625 - 20 -180.07748413085937 - 30 -0.0 - 10 -162.00248718261719 - 20 -180.02998352050781 - 30 -0.0 - 10 -161.83999633789062 - 20 -179.96748352050781 - 30 -0.0 - 10 -161.67999267578125 - 20 -179.88499450683594 - 30 -0.0 - 10 -161.39248657226562 - 20 -179.677490234375 - 30 -0.0 - 10 -161.15998840332031 - 20 -179.42498779296875 - 30 -0.0 - 10 -160.98248291015625 - 20 -179.13748168945312 - 30 -0.0 - 10 -160.91499328613281 - 20 -178.98248291015625 - 30 -0.0 - 10 -160.864990234375 - 20 -178.82249450683594 - 30 -0.0 - 10 -160.82998657226562 - 20 -178.65998840332031 - 30 -0.0 - 10 -160.80998229980469 - 20 -178.49249267578125 - 30 -0.0 - 10 -160.80499267578125 - 20 -178.32249450683594 - 30 -0.0 - 10 -160.81748962402344 - 20 -178.15498352050781 - 30 -0.0 - 10 -160.84748840332031 - 20 -177.9849853515625 - 30 -0.0 - 10 -160.89498901367187 - 20 -177.81748962402344 - 30 -0.0 - 10 -160.95748901367187 - 20 -177.65498352050781 - 30 -0.0 - 10 -161.03999328613281 - 20 -177.4949951171875 - 30 -0.0 - 10 -161.24748229980469 - 20 -177.20748901367187 - 30 -0.0 - 10 -161.49998474121094 - 20 -176.97248840332031 - 30 -0.0 - 10 -161.78749084472656 - 20 -176.7974853515625 - 30 -0.0 - 10 -161.94248962402344 - 20 -176.72999572753906 - 30 -0.0 - 10 -162.10249328613281 - 20 -176.67999267578125 - 30 -0.0 - 10 -162.26498413085937 - 20 -176.64248657226562 - 30 -0.0 - 10 -162.4324951171875 - 20 -176.62248229980469 - 30 -0.0 - 10 -162.60249328613281 - 20 -176.6199951171875 - 30 -0.0 - 10 -162.76998901367187 - 20 -176.63249206542969 - 30 -0.0 - 10 -162.93998718261719 - 20 -176.66249084472656 - 30 -0.0 - 10 -163.10748291015625 - 20 -176.70999145507812 - 30 -0.0 - 10 -163.26998901367188 - 20 -176.77249145507812 - 30 -0.0 - 10 -163.42999267578125 - 20 -176.85499572753906 - 30 -0.0 - 0 -LWPOLYLINE - 5 -59 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -53 - 70 -0 - 10 -179.90498352050781 - 20 -161.66499328613281 - 30 -0.0 - 10 -179.98748779296875 - 20 -161.82498168945313 - 30 -0.0 - 10 -180.04998779296875 - 20 -161.98748779296875 - 30 -0.0 - 10 -180.09748840332031 - 20 -162.15498352050781 - 30 -0.0 - 10 -180.12748718261719 - 20 -162.32498168945312 - 30 -0.0 - 10 -180.13998413085937 - 20 -162.49249267578125 - 30 -0.0 - 10 -180.13499450683594 - 20 -162.66249084472656 - 30 -0.0 - 10 -180.114990234375 - 20 -162.82998657226562 - 30 -0.0 - 10 -180.07998657226562 - 20 -162.99249267578125 - 30 -0.0 - 10 -180.02998352050781 - 20 -163.15249633789063 - 30 -0.0 - 10 -179.96249389648437 - 20 -163.3074951171875 - 30 -0.0 - 10 -179.78498840332031 - 20 -163.59498596191406 - 30 -0.0 - 10 -179.552490234375 - 20 -163.84748840332031 - 30 -0.0 - 10 -179.26498413085937 - 20 -164.05499267578125 - 30 -0.0 - 10 -179.10499572753906 - 20 -164.13748168945312 - 30 -0.0 - 10 -178.94248962402344 - 20 -164.19998168945312 - 30 -0.0 - 10 -178.77499389648437 - 20 -164.24748229980469 - 30 -0.0 - 10 -178.60499572753906 - 20 -164.27748107910156 - 30 -0.0 - 10 -178.43748474121094 - 20 -164.28999328613281 - 30 -0.0 - 10 -178.26748657226562 - 20 -164.28749084472656 - 30 -0.0 - 10 -178.09999084472656 - 20 -164.26748657226562 - 30 -0.0 - 10 -177.93748474121094 - 20 -164.22999572753906 - 30 -0.0 - 10 -177.77748107910156 - 20 -164.17999267578125 - 30 -0.0 - 10 -177.62248229980469 - 20 -164.11248779296875 - 30 -0.0 - 10 -177.33248901367187 - 20 -163.93748474121094 - 30 -0.0 - 10 -177.07998657226562 - 20 -163.70248413085937 - 30 -0.0 - 10 -176.87248229980469 - 20 -163.41499328613281 - 30 -0.0 - 10 -176.78999328613281 - 20 -163.25498962402344 - 30 -0.0 - 10 -176.72749328613281 - 20 -163.09248352050781 - 30 -0.0 - 10 -176.67999267578125 - 20 -162.92498779296875 - 30 -0.0 - 10 -176.65248107910156 - 20 -162.75498962402344 - 30 -0.0 - 10 -176.63998413085937 - 20 -162.58749389648438 - 30 -0.0 - 10 -176.64248657226562 - 20 -162.41749572753906 - 30 -0.0 - 10 -176.66249084472656 - 20 -162.24998474121094 - 30 -0.0 - 10 -176.69998168945312 - 20 -162.08749389648437 - 30 -0.0 - 10 -176.74998474121094 - 20 -161.927490234375 - 30 -0.0 - 10 -176.81748962402344 - 20 -161.77249145507812 - 30 -0.0 - 10 -176.99249267578125 - 20 -161.4849853515625 - 30 -0.0 - 10 -177.22749328613281 - 20 -161.23248291015625 - 30 -0.0 - 10 -177.51498413085937 - 20 -161.02499389648437 - 30 -0.0 - 10 -177.67498779296875 - 20 -160.94248962402344 - 30 -0.0 - 10 -177.83749389648437 - 20 -160.87998962402344 - 30 -0.0 - 10 -178.00498962402344 - 20 -160.83248901367187 - 30 -0.0 - 10 -178.17498779296875 - 20 -160.802490234375 - 30 -0.0 - 10 -178.34248352050781 - 20 -160.78999328613281 - 30 -0.0 - 10 -178.51248168945312 - 20 -160.79498291015625 - 30 -0.0 - 10 -178.67999267578125 - 20 -160.81498718261719 - 30 -0.0 - 10 -178.84248352050781 - 20 -160.84999084472656 - 30 -0.0 - 10 -179.00248718261719 - 20 -160.89999389648437 - 30 -0.0 - 10 -179.15748596191406 - 20 -160.96748352050781 - 30 -0.0 - 10 -179.44499206542969 - 20 -161.14498901367187 - 30 -0.0 - 10 -179.69749450683594 - 20 -161.37748718261719 - 30 -0.0 - 10 -179.90498352050781 - 20 -161.66499328613281 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5A -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -49 - 70 -0 - 10 -201.76498413085937 - 20 -156.74998474121094 - 30 -0.0 - 10 -201.75498962402344 - 20 -156.927490234375 - 30 -0.0 - 10 -201.72998046875 - 20 -157.10249328613281 - 30 -0.0 - 10 -201.68748474121094 - 20 -157.26998901367187 - 30 -0.0 - 10 -201.62748718261719 - 20 -157.42999267578125 - 30 -0.0 - 10 -201.46748352050781 - 20 -157.72749328613281 - 30 -0.0 - 10 -201.25248718261719 - 20 -157.98748779296875 - 30 -0.0 - 10 -200.9949951171875 - 20 -158.19998168945312 - 30 -0.0 - 10 -200.69749450683594 - 20 -158.36248779296875 - 30 -0.0 - 10 -200.53498840332031 - 20 -158.41998291015625 - 30 -0.0 - 10 -200.36749267578125 - 20 -158.46499633789062 - 30 -0.0 - 10 -200.19499206542969 - 20 -158.489990234375 - 30 -0.0 - 10 -200.01498413085937 - 20 -158.49998474121094 - 30 -0.0 - 10 -199.83749389648437 - 20 -158.489990234375 - 30 -0.0 - 10 -199.66249084472656 - 20 -158.46499633789062 - 30 -0.0 - 10 -199.4949951171875 - 20 -158.41998291015625 - 30 -0.0 - 10 -199.33499145507812 - 20 -158.36248779296875 - 30 -0.0 - 10 -199.03749084472656 - 20 -158.19998168945312 - 30 -0.0 - 10 -198.77748107910156 - 20 -157.98748779296875 - 30 -0.0 - 10 -198.56498718261719 - 20 -157.72749328613281 - 30 -0.0 - 10 -198.40248107910156 - 20 -157.42999267578125 - 30 -0.0 - 10 -198.34498596191406 - 20 -157.26998901367187 - 30 -0.0 - 10 -198.29998779296875 - 20 -157.10249328613281 - 30 -0.0 - 10 -198.27499389648437 - 20 -156.927490234375 - 30 -0.0 - 10 -198.26498413085937 - 20 -156.74998474121094 - 30 -0.0 - 10 -198.27499389648437 - 20 -156.56999206542969 - 30 -0.0 - 10 -198.29998779296875 - 20 -156.39749145507812 - 30 -0.0 - 10 -198.34498596191406 - 20 -156.22999572753906 - 30 -0.0 - 10 -198.40248107910156 - 20 -156.06748962402344 - 30 -0.0 - 10 -198.56498718261719 - 20 -155.76998901367187 - 30 -0.0 - 10 -198.77748107910156 - 20 -155.50999450683594 - 30 -0.0 - 10 -199.03749084472656 - 20 -155.2974853515625 - 30 -0.0 - 10 -199.33499145507812 - 20 -155.13499450683594 - 30 -0.0 - 10 -199.4949951171875 - 20 -155.07748413085937 - 30 -0.0 - 10 -199.66249084472656 - 20 -155.03248596191406 - 30 -0.0 - 10 -199.83749389648437 - 20 -155.00749206542969 - 30 -0.0 - 10 -200.01498413085937 - 20 -154.99748229980469 - 30 -0.0 - 10 -200.19499206542969 - 20 -155.00749206542969 - 30 -0.0 - 10 -200.36749267578125 - 20 -155.03248596191406 - 30 -0.0 - 10 -200.53498840332031 - 20 -155.07748413085937 - 30 -0.0 - 10 -200.69749450683594 - 20 -155.13499450683594 - 30 -0.0 - 10 -200.9949951171875 - 20 -155.2974853515625 - 30 -0.0 - 10 -201.25248718261719 - 20 -155.50999450683594 - 30 -0.0 - 10 -201.46748352050781 - 20 -155.76998901367187 - 30 -0.0 - 10 -201.62748718261719 - 20 -156.06748962402344 - 30 -0.0 - 10 -201.68748474121094 - 20 -156.22999572753906 - 30 -0.0 - 10 -201.72998046875 - 20 -156.39749145507812 - 30 -0.0 - 10 -201.75498962402344 - 20 -156.56999206542969 - 30 -0.0 - 10 -201.76498413085937 - 20 -156.74998474121094 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5B -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -53 - 70 -0 - 10 -223.15748596191406 - 20 -163.4224853515625 - 30 -0.0 - 10 -222.94998168945313 - 20 -163.70999145507812 - 30 -0.0 - 10 -222.69749450683594 - 20 -163.94248962402344 - 30 -0.0 - 10 -222.40998840332031 - 20 -164.1199951171875 - 30 -0.0 - 10 -222.25498962402344 - 20 -164.18748474121094 - 30 -0.0 - 10 -222.09498596191406 - 20 -164.23748779296875 - 30 -0.0 - 10 -221.93247985839844 - 20 -164.27249145507812 - 30 -0.0 - 10 -221.76498413085937 - 20 -164.29249572753906 - 30 -0.0 - 10 -221.59498596191406 - 20 -164.2974853515625 - 30 -0.0 - 10 -221.427490234375 - 20 -164.28498840332031 - 30 -0.0 - 10 -221.25749206542969 - 20 -164.25498962402344 - 30 -0.0 - 10 -221.08998107910156 - 20 -164.20748901367188 - 30 -0.0 - 10 -220.927490234375 - 20 -164.14498901367187 - 30 -0.0 - 10 -220.76748657226562 - 20 -164.06248474121094 - 30 -0.0 - 10 -220.47998046875 - 20 -163.85499572753906 - 30 -0.0 - 10 -220.24497985839844 - 20 -163.60249328613281 - 30 -0.0 - 10 -220.06999206542969 - 20 -163.31498718261719 - 30 -0.0 - 10 -220.00248718261719 - 20 -163.15998840332031 - 30 -0.0 - 10 -219.95248413085937 - 20 -162.99998474121094 - 30 -0.0 - 10 -219.91499328613281 - 20 -162.83749389648437 - 30 -0.0 - 10 -219.89498901367187 - 20 -162.66998291015625 - 30 -0.0 - 10 -219.89248657226562 - 20 -162.49998474121094 - 30 -0.0 - 10 -219.90498352050781 - 20 -162.33248901367187 - 30 -0.0 - 10 -219.93247985839844 - 20 -162.16249084472656 - 30 -0.0 - 10 -219.97998046875 - 20 -161.9949951171875 - 30 -0.0 - 10 -220.04248046875 - 20 -161.83248901367187 - 30 -0.0 - 10 -220.12498474121094 - 20 -161.6724853515625 - 30 -0.0 - 10 -220.33248901367187 - 20 -161.38499450683594 - 30 -0.0 - 10 -220.58499145507812 - 20 -161.14999389648437 - 30 -0.0 - 10 -220.87498474121094 - 20 -160.97499084472656 - 30 -0.0 - 10 -221.02998352050781 - 20 -160.90748596191406 - 30 -0.0 - 10 -221.18998718261719 - 20 -160.85748291015625 - 30 -0.0 - 10 -221.35249328613281 - 20 -160.81999206542969 - 30 -0.0 - 10 -221.51998901367187 - 20 -160.79998779296875 - 30 -0.0 - 10 -221.68998718261719 - 20 -160.7974853515625 - 30 -0.0 - 10 -221.85748291015625 - 20 -160.80998229980469 - 30 -0.0 - 10 -222.02748107910156 - 20 -160.83999633789063 - 30 -0.0 - 10 -222.19499206542969 - 20 -160.88748168945313 - 30 -0.0 - 10 -222.35748291015625 - 20 -160.94998168945312 - 30 -0.0 - 10 -222.51748657226562 - 20 -161.03248596191406 - 30 -0.0 - 10 -222.80499267578125 - 20 -161.239990234375 - 30 -0.0 - 10 -223.03749084472656 - 20 -161.49249267578125 - 30 -0.0 - 10 -223.21498107910156 - 20 -161.77998352050781 - 30 -0.0 - 10 -223.28248596191406 - 20 -161.93498229980469 - 30 -0.0 - 10 -223.33248901367187 - 20 -162.09498596191406 - 30 -0.0 - 10 -223.36749267578125 - 20 -162.25749206542969 - 30 -0.0 - 10 -223.38748168945312 - 20 -162.42498779296875 - 30 -0.0 - 10 -223.39248657226562 - 20 -162.59498596191406 - 30 -0.0 - 10 -223.37998962402344 - 20 -162.76248168945312 - 30 -0.0 - 10 -223.34999084472656 - 20 -162.9324951171875 - 30 -0.0 - 10 -223.302490234375 - 20 -163.09999084472656 - 30 -0.0 - 10 -223.239990234375 - 20 -163.26248168945312 - 30 -0.0 - 10 -223.15748596191406 - 20 -163.4224853515625 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5C -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -53 - 70 -0 - 10 -238.34498596191406 - 20 -179.89749145507812 - 30 -0.0 - 10 -238.18498229980469 - 20 -179.97999572753906 - 30 -0.0 - 10 -238.02249145507812 - 20 -180.04249572753906 - 30 -0.0 - 10 -237.85498046875 - 20 -180.08998107910156 - 30 -0.0 - 10 -237.68498229980469 - 20 -180.1199951171875 - 30 -0.0 - 10 -237.51748657226562 - 20 -180.13249206542969 - 30 -0.0 - 10 -237.34748840332031 - 20 -180.12748718261719 - 30 -0.0 - 10 -237.17999267578125 - 20 -180.10748291015625 - 30 -0.0 - 10 -237.01748657226562 - 20 -180.07249450683594 - 30 -0.0 - 10 -236.85748291015625 - 20 -180.02249145507812 - 30 -0.0 - 10 -236.70248413085937 - 20 -179.95498657226562 - 30 -0.0 - 10 -236.41499328613281 - 20 -179.77748107910156 - 30 -0.0 - 10 -236.16249084472656 - 20 -179.54498291015625 - 30 -0.0 - 10 -235.95498657226562 - 20 -179.25749206542969 - 30 -0.0 - 10 -235.87248229980469 - 20 -179.09748840332031 - 30 -0.0 - 10 -235.80998229980469 - 20 -178.93498229980469 - 30 -0.0 - 10 -235.76248168945312 - 20 -178.76748657226562 - 30 -0.0 - 10 -235.73248291015625 - 20 -178.59748840332031 - 30 -0.0 - 10 -235.71998596191406 - 20 -178.42999267578125 - 30 -0.0 - 10 -235.72248840332031 - 20 -178.25999450683594 - 30 -0.0 - 10 -235.74249267578125 - 20 -178.09248352050781 - 30 -0.0 - 10 -235.77998352050781 - 20 -177.92999267578125 - 30 -0.0 - 10 -235.82998657226562 - 20 -177.76998901367188 - 30 -0.0 - 10 -235.89749145507812 - 20 -177.614990234375 - 30 -0.0 - 10 -236.07249450683594 - 20 -177.32498168945313 - 30 -0.0 - 10 -236.30747985839844 - 20 -177.07249450683594 - 30 -0.0 - 10 -236.59498596191406 - 20 -176.864990234375 - 30 -0.0 - 10 -236.75498962402344 - 20 -176.78248596191406 - 30 -0.0 - 10 -236.91748046875 - 20 -176.71998596191406 - 30 -0.0 - 10 -237.08499145507812 - 20 -176.6724853515625 - 30 -0.0 - 10 -237.25498962402344 - 20 -176.64498901367187 - 30 -0.0 - 10 -237.4224853515625 - 20 -176.63249206542969 - 30 -0.0 - 10 -237.59248352050781 - 20 -176.63499450683594 - 30 -0.0 - 10 -237.75999450683594 - 20 -176.65498352050781 - 30 -0.0 - 10 -237.9224853515625 - 20 -176.69248962402344 - 30 -0.0 - 10 -238.08248901367188 - 20 -176.74249267578125 - 30 -0.0 - 10 -238.23748779296875 - 20 -176.80998229980469 - 30 -0.0 - 10 -238.52499389648437 - 20 -176.9849853515625 - 30 -0.0 - 10 -238.77748107910156 - 20 -177.21998596191406 - 30 -0.0 - 10 -238.9849853515625 - 20 -177.50749206542969 - 30 -0.0 - 10 -239.06748962402344 - 20 -177.66749572753906 - 30 -0.0 - 10 -239.12998962402344 - 20 -177.82998657226562 - 30 -0.0 - 10 -239.177490234375 - 20 -177.99748229980469 - 30 -0.0 - 10 -239.20748901367187 - 20 -178.16499328613281 - 30 -0.0 - 10 -239.21998596191406 - 20 -178.33499145507812 - 30 -0.0 - 10 -239.21748352050781 - 20 -178.50248718261719 - 30 -0.0 - 10 -239.19749450683594 - 20 -178.66998291015625 - 30 -0.0 - 10 -239.15998840332031 - 20 -178.83499145507812 - 30 -0.0 - 10 -239.1099853515625 - 20 -178.9949951171875 - 30 -0.0 - 10 -239.04248046875 - 20 -179.14999389648437 - 30 -0.0 - 10 -238.86749267578125 - 20 -179.43748474121094 - 30 -0.0 - 10 -238.63249206542969 - 20 -179.68998718261719 - 30 -0.0 - 10 -238.34498596191406 - 20 -179.89749145507812 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5D -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -49 - 70 -0 - 10 -243.25999450683594 - 20 -201.75999450683594 - 30 -0.0 - 10 -243.08248901367187 - 20 -201.74998474121094 - 30 -0.0 - 10 -242.90748596191406 - 20 -201.72499084472656 - 30 -0.0 - 10 -242.739990234375 - 20 -201.67999267578125 - 30 -0.0 - 10 -242.57998657226562 - 20 -201.62248229980469 - 30 -0.0 - 10 -242.28248596191406 - 20 -201.45999145507812 - 30 -0.0 - 10 -242.02249145507812 - 20 -201.24748229980469 - 30 -0.0 - 10 -241.80998229980469 - 20 -200.98748779296875 - 30 -0.0 - 10 -241.64749145507812 - 20 -200.68998718261719 - 30 -0.0 - 10 -241.58998107910156 - 20 -200.52998352050781 - 30 -0.0 - 10 -241.54498291015625 - 20 -200.36248779296875 - 30 -0.0 - 10 -241.51998901367188 - 20 -200.18748474121094 - 30 -0.0 - 10 -241.50999450683594 - 20 -200.00999450683594 - 30 -0.0 - 10 -241.51998901367188 - 20 -199.82998657226562 - 30 -0.0 - 10 -241.54498291015625 - 20 -199.65748596191406 - 30 -0.0 - 10 -241.58998107910156 - 20 -199.489990234375 - 30 -0.0 - 10 -241.64749145507812 - 20 -199.32748413085937 - 30 -0.0 - 10 -241.80998229980469 - 20 -199.02998352050781 - 30 -0.0 - 10 -242.02249145507812 - 20 -198.77249145507812 - 30 -0.0 - 10 -242.28248596191406 - 20 -198.5574951171875 - 30 -0.0 - 10 -242.57998657226562 - 20 -198.39749145507812 - 30 -0.0 - 10 -242.739990234375 - 20 -198.33749389648437 - 30 -0.0 - 10 -242.90748596191406 - 20 -198.29498291015625 - 30 -0.0 - 10 -243.08248901367187 - 20 -198.26998901367187 - 30 -0.0 - 10 -243.25999450683594 - 20 -198.25999450683594 - 30 -0.0 - 10 -243.43998718261719 - 20 -198.26998901367187 - 30 -0.0 - 10 -243.61248779296875 - 20 -198.29498291015625 - 30 -0.0 - 10 -243.77998352050781 - 20 -198.33749389648437 - 30 -0.0 - 10 -243.94248962402344 - 20 -198.39749145507812 - 30 -0.0 - 10 -244.239990234375 - 20 -198.5574951171875 - 30 -0.0 - 10 -244.49748229980469 - 20 -198.77249145507812 - 30 -0.0 - 10 -244.71249389648437 - 20 -199.02998352050781 - 30 -0.0 - 10 -244.87248229980469 - 20 -199.32748413085937 - 30 -0.0 - 10 -244.93247985839844 - 20 -199.489990234375 - 30 -0.0 - 10 -244.97499084472656 - 20 -199.65748596191406 - 30 -0.0 - 10 -244.99998474121094 - 20 -199.82998657226562 - 30 -0.0 - 10 -245.00999450683594 - 20 -200.00999450683594 - 30 -0.0 - 10 -244.99998474121094 - 20 -200.18748474121094 - 30 -0.0 - 10 -244.97499084472656 - 20 -200.36248779296875 - 30 -0.0 - 10 -244.93247985839844 - 20 -200.52998352050781 - 30 -0.0 - 10 -244.87248229980469 - 20 -200.68998718261719 - 30 -0.0 - 10 -244.71249389648437 - 20 -200.98748779296875 - 30 -0.0 - 10 -244.49748229980469 - 20 -201.24748229980469 - 30 -0.0 - 10 -244.239990234375 - 20 -201.45999145507812 - 30 -0.0 - 10 -243.94248962402344 - 20 -201.62248229980469 - 30 -0.0 - 10 -243.77998352050781 - 20 -201.67999267578125 - 30 -0.0 - 10 -243.61248779296875 - 20 -201.72499084472656 - 30 -0.0 - 10 -243.43998718261719 - 20 -201.74998474121094 - 30 -0.0 - 10 -243.25999450683594 - 20 -201.75999450683594 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5E -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -53 - 70 -0 - 10 -236.58749389648437 - 20 -223.14749145507812 - 30 -0.0 - 10 -236.29998779296875 - 20 -222.93998718261719 - 30 -0.0 - 10 -236.06498718261719 - 20 -222.68748474121094 - 30 -0.0 - 10 -235.88998413085937 - 20 -222.39999389648437 - 30 -0.0 - 10 -235.82249450683594 - 20 -222.24497985839844 - 30 -0.0 - 10 -235.77249145507812 - 20 -222.08499145507812 - 30 -0.0 - 10 -235.7349853515625 - 20 -221.9224853515625 - 30 -0.0 - 10 -235.71498107910156 - 20 -221.75498962402344 - 30 -0.0 - 10 -235.71249389648437 - 20 -221.58499145507812 - 30 -0.0 - 10 -235.72499084472656 - 20 -221.41748046875 - 30 -0.0 - 10 -235.75248718261719 - 20 -221.24748229980469 - 30 -0.0 - 10 -235.79998779296875 - 20 -221.07998657226562 - 30 -0.0 - 10 -235.86248779296875 - 20 -220.91748046875 - 30 -0.0 - 10 -235.94499206542969 - 20 -220.75749206542969 - 30 -0.0 - 10 -236.15248107910156 - 20 -220.46998596191406 - 30 -0.0 - 10 -236.40498352050781 - 20 -220.23748779296875 - 30 -0.0 - 10 -236.69499206542969 - 20 -220.05998229980469 - 30 -0.0 - 10 -236.84999084472656 - 20 -219.99249267578125 - 30 -0.0 - 10 -237.00999450683594 - 20 -219.94248962402344 - 30 -0.0 - 10 -237.1724853515625 - 20 -219.90748596191406 - 30 -0.0 - 10 -237.33998107910156 - 20 -219.88748168945312 - 30 -0.0 - 10 -237.50999450683594 - 20 -219.88249206542969 - 30 -0.0 - 10 -237.677490234375 - 20 -219.89498901367187 - 30 -0.0 - 10 -237.84748840332031 - 20 -219.92498779296875 - 30 -0.0 - 10 -238.01498413085937 - 20 -219.97248840332031 - 30 -0.0 - 10 -238.177490234375 - 20 -220.03498840332031 - 30 -0.0 - 10 -238.33749389648437 - 20 -220.11749267578125 - 30 -0.0 - 10 -238.62498474121094 - 20 -220.32498168945312 - 30 -0.0 - 10 -238.85748291015625 - 20 -220.57748413085937 - 30 -0.0 - 10 -239.03498840332031 - 20 -220.864990234375 - 30 -0.0 - 10 -239.09999084472656 - 20 -221.01998901367187 - 30 -0.0 - 10 -239.15248107910156 - 20 -221.17999267578125 - 30 -0.0 - 10 -239.18748474121094 - 20 -221.34248352050781 - 30 -0.0 - 10 -239.20748901367187 - 20 -221.50999450683594 - 30 -0.0 - 10 -239.20999145507812 - 20 -221.67999267578125 - 30 -0.0 - 10 -239.19749450683594 - 20 -221.84748840332031 - 30 -0.0 - 10 -239.16998291015625 - 20 -222.01748657226562 - 30 -0.0 - 10 -239.12248229980469 - 20 -222.18498229980469 - 30 -0.0 - 10 -239.05998229980469 - 20 -222.34748840332031 - 30 -0.0 - 10 -238.97749328613281 - 20 -222.50749206542969 - 30 -0.0 - 10 -238.76998901367188 - 20 -222.79498291015625 - 30 -0.0 - 10 -238.51748657226562 - 20 -223.02998352050781 - 30 -0.0 - 10 -238.22749328613281 - 20 -223.20498657226562 - 30 -0.0 - 10 -238.07249450683594 - 20 -223.27249145507812 - 30 -0.0 - 10 -237.91499328613281 - 20 -223.32249450683594 - 30 -0.0 - 10 -237.74998474121094 - 20 -223.3599853515625 - 30 -0.0 - 10 -237.58248901367187 - 20 -223.37998962402344 - 30 -0.0 - 10 -237.41499328613281 - 20 -223.38249206542969 - 30 -0.0 - 10 -237.24497985839844 - 20 -223.36997985839844 - 30 -0.0 - 10 -237.07748413085937 - 20 -223.33998107910156 - 30 -0.0 - 10 -236.90998840332031 - 20 -223.29248046875 - 30 -0.0 - 10 -236.74748229980469 - 20 -223.22998046875 - 30 -0.0 - 10 -236.58749389648437 - 20 -223.14749145507812 - 30 -0.0 - 0 -LWPOLYLINE - 5 -5F -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -53 - 70 -0 - 10 -220.1099853515625 - 20 -238.33499145507812 - 30 -0.0 - 10 -220.02748107910156 - 20 -238.17498779296875 - 30 -0.0 - 10 -219.96498107910156 - 20 -238.01248168945312 - 30 -0.0 - 10 -219.91748046875 - 20 -237.84498596191406 - 30 -0.0 - 10 -219.88998413085937 - 20 -237.67498779296875 - 30 -0.0 - 10 -219.87748718261719 - 20 -237.50749206542969 - 30 -0.0 - 10 -219.87998962402344 - 20 -237.33749389648437 - 30 -0.0 - 10 -219.89999389648437 - 20 -237.16998291015625 - 30 -0.0 - 10 -219.93498229980469 - 20 -237.00749206542969 - 30 -0.0 - 10 -219.98748779296875 - 20 -236.84748840332031 - 30 -0.0 - 10 -220.052490234375 - 20 -236.69248962402344 - 30 -0.0 - 10 -220.22998046875 - 20 -236.40498352050781 - 30 -0.0 - 10 -220.46249389648437 - 20 -236.15248107910156 - 30 -0.0 - 10 -220.74998474121094 - 20 -235.94499206542969 - 30 -0.0 - 10 -220.90998840332031 - 20 -235.86248779296875 - 30 -0.0 - 10 -221.07249450683594 - 20 -235.79998779296875 - 30 -0.0 - 10 -221.239990234375 - 20 -235.75248718261719 - 30 -0.0 - 10 -221.40998840332031 - 20 -235.72248840332031 - 30 -0.0 - 10 -221.57748413085937 - 20 -235.70999145507812 - 30 -0.0 - 10 -221.74748229980469 - 20 -235.71498107910156 - 30 -0.0 - 10 -221.91499328613281 - 20 -235.7349853515625 - 30 -0.0 - 10 -222.07748413085937 - 20 -235.76998901367188 - 30 -0.0 - 10 -222.23748779296875 - 20 -235.81999206542969 - 30 -0.0 - 10 -222.39248657226562 - 20 -235.88748168945312 - 30 -0.0 - 10 -222.68247985839844 - 20 -236.06498718261719 - 30 -0.0 - 10 -222.93498229980469 - 20 -236.2974853515625 - 30 -0.0 - 10 -223.14248657226562 - 20 -236.58499145507812 - 30 -0.0 - 10 -223.22499084472656 - 20 -236.74497985839844 - 30 -0.0 - 10 -223.28749084472656 - 20 -236.90748596191406 - 30 -0.0 - 10 -223.33499145507812 - 20 -237.07498168945313 - 30 -0.0 - 10 -223.36248779296875 - 20 -237.24497985839844 - 30 -0.0 - 10 -223.37498474121094 - 20 -237.41249084472656 - 30 -0.0 - 10 -223.37248229980469 - 20 -237.58248901367187 - 30 -0.0 - 10 -223.35249328613281 - 20 -237.74998474121094 - 30 -0.0 - 10 -223.31748962402344 - 20 -237.91249084472656 - 30 -0.0 - 10 -223.26498413085937 - 20 -238.07249450683594 - 30 -0.0 - 10 -223.19749450683594 - 20 -238.22749328613281 - 30 -0.0 - 10 -223.02249145507812 - 20 -238.51498413085937 - 30 -0.0 - 10 -222.78749084472656 - 20 -238.76748657226562 - 30 -0.0 - 10 -222.49998474121094 - 20 -238.97499084472656 - 30 -0.0 - 10 -222.33998107910156 - 20 -239.05747985839844 - 30 -0.0 - 10 -222.177490234375 - 20 -239.11997985839844 - 30 -0.0 - 10 -222.00999450683594 - 20 -239.16748046875 - 30 -0.0 - 10 -221.84248352050781 - 20 -239.19749450683594 - 30 -0.0 - 10 -221.6724853515625 - 20 -239.20999145507812 - 30 -0.0 - 10 -221.50498962402344 - 20 -239.20748901367187 - 30 -0.0 - 10 -221.33749389648437 - 20 -239.18748474121094 - 30 -0.0 - 10 -221.1724853515625 - 20 -239.14999389648437 - 30 -0.0 - 10 -221.01248168945312 - 20 -239.09999084472656 - 30 -0.0 - 10 -220.85748291015625 - 20 -239.03248596191406 - 30 -0.0 - 10 -220.56999206542969 - 20 -238.85748291015625 - 30 -0.0 - 10 -220.31748962402344 - 20 -238.62248229980469 - 30 -0.0 - 10 -220.1099853515625 - 20 -238.33499145507812 - 30 -0.0 - 0 -LWPOLYLINE - 5 -60 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -97 - 70 -0 - 10 -200.91998291015625 - 20 -165.00497436523437 - 30 -0.0 - 10 -201.81748962402344 - 20 -165.0374755859375 - 30 -0.0 - 10 -202.70999145507812 - 20 -165.094970703125 - 30 -0.0 - 10 -203.59498596191406 - 20 -165.17247009277344 - 30 -0.0 - 10 -204.47499084472656 - 20 -165.27247619628906 - 30 -0.0 - 10 -205.34748840332031 - 20 -165.39497375488281 - 30 -0.0 - 10 -206.21249389648437 - 20 -165.53997802734375 - 30 -0.0 - 10 -207.06999206542969 - 20 -165.70248413085937 - 30 -0.0 - 10 -207.91998291015625 - 20 -165.88998413085937 - 30 -0.0 - 10 -208.76248168945312 - 20 -166.094970703125 - 30 -0.0 - 10 -209.59748840332031 - 20 -166.31997680664062 - 30 -0.0 - 10 -210.42498779296875 - 20 -166.56497192382812 - 30 -0.0 - 10 -211.24249267578125 - 20 -166.83247375488281 - 30 -0.0 - 10 -212.04998779296875 - 20 -167.11747741699219 - 30 -0.0 - 10 -212.84999084472656 - 20 -167.41998291015625 - 30 -0.0 - 10 -213.63998413085937 - 20 -167.74247741699219 - 30 -0.0 - 10 -214.41998291015625 - 20 -168.08497619628906 - 30 -0.0 - 10 -215.18998718261719 - 20 -168.44497680664062 - 30 -0.0 - 10 -215.94998168945312 - 20 -168.82247924804687 - 30 -0.0 - 10 -216.69998168945312 - 20 -169.21748352050781 - 30 -0.0 - 10 -217.43748474121094 - 20 -169.62997436523437 - 30 -0.0 - 10 -218.16499328613281 - 20 -170.05998229980469 - 30 -0.0 - 10 -218.87998962402344 - 20 -170.50747680664062 - 30 -0.0 - 10 -219.58499145507812 - 20 -170.969970703125 - 30 -0.0 - 10 -220.27748107910156 - 20 -171.44998168945312 - 30 -0.0 - 10 -220.95748901367188 - 20 -171.94747924804687 - 30 -0.0 - 10 -221.62498474121094 - 20 -172.45747375488281 - 30 -0.0 - 10 -222.27748107910156 - 20 -172.98497009277344 - 30 -0.0 - 10 -222.91998291015625 - 20 -173.52748107910156 - 30 -0.0 - 10 -223.5474853515625 - 20 -174.08497619628906 - 30 -0.0 - 10 -224.76498413085937 - 20 -175.24497985839844 - 30 -0.0 - 10 -225.9224853515625 - 20 -176.45997619628906 - 30 -0.0 - 10 -226.47998046875 - 20 -177.08998107910156 - 30 -0.0 - 10 -226.88090515136719 - 20 -177.56294250488281 - 30 -0.0 - 10 -208.92091369628906 - 20 -187.93214416503906 - 30 -0.0 - 10 -208.39498901367187 - 20 -187.55998229980469 - 30 -0.0 - 10 -207.78749084472656 - 20 -187.16998291015625 - 30 -0.0 - 10 -207.15998840332031 - 20 -186.80747985839844 - 30 -0.0 - 10 -206.51248168945313 - 20 -186.47747802734375 - 30 -0.0 - 10 -205.84748840332031 - 20 -186.17497253417969 - 30 -0.0 - 10 -205.16748046875 - 20 -185.907470703125 - 30 -0.0 - 10 -204.46998596191406 - 20 -185.67247009277344 - 30 -0.0 - 10 -203.75749206542969 - 20 -185.469970703125 - 30 -0.0 - 10 -203.03248596191406 - 20 -185.30247497558594 - 30 -0.0 - 10 -202.29498291015625 - 20 -185.16998291015625 - 30 -0.0 - 10 -201.54248046875 - 20 -185.07498168945312 - 30 -0.0 - 10 -200.78248596191406 - 20 -185.01747131347656 - 30 -0.0 - 10 -200.00999450683594 - 20 -184.99748229980469 - 30 -0.0 - 10 -199.23748779296875 - 20 -185.01747131347656 - 30 -0.0 - 10 -198.47499084472656 - 20 -185.07498168945312 - 30 -0.0 - 10 -197.72499084472656 - 20 -185.16998291015625 - 30 -0.0 - 10 -196.98748779296875 - 20 -185.30247497558594 - 30 -0.0 - 10 -196.25999450683594 - 20 -185.469970703125 - 30 -0.0 - 10 -195.54998779296875 - 20 -185.67247009277344 - 30 -0.0 - 10 -194.85249328613281 - 20 -185.907470703125 - 30 -0.0 - 10 -194.16998291015625 - 20 -186.17497253417969 - 30 -0.0 - 10 -193.50498962402344 - 20 -186.47747802734375 - 30 -0.0 - 10 -192.8599853515625 - 20 -186.80747985839844 - 30 -0.0 - 10 -192.22998046875 - 20 -187.16998291015625 - 30 -0.0 - 10 -191.62248229980469 - 20 -187.55998229980469 - 30 -0.0 - 10 -191.10592651367187 - 20 -187.92706298828125 - 30 -0.0 - 10 -173.1539306640625 - 20 -177.56245422363281 - 30 -0.0 - 10 -173.55499267578125 - 20 -177.08747863769531 - 30 -0.0 - 10 -174.11248779296875 - 20 -176.45997619628906 - 30 -0.0 - 10 -175.26998901367187 - 20 -175.24247741699219 - 30 -0.0 - 10 -176.48748779296875 - 20 -174.08497619628906 - 30 -0.0 - 10 -177.114990234375 - 20 -173.52748107910156 - 30 -0.0 - 10 -177.75498962402344 - 20 -172.98497009277344 - 30 -0.0 - 10 -178.40998840332031 - 20 -172.45747375488281 - 30 -0.0 - 10 -179.07748413085937 - 20 -171.94497680664062 - 30 -0.0 - 10 -179.75749206542969 - 20 -171.44998168945312 - 30 -0.0 - 10 -180.44998168945312 - 20 -170.969970703125 - 30 -0.0 - 10 -181.15498352050781 - 20 -170.50747680664062 - 30 -0.0 - 10 -181.8699951171875 - 20 -170.05998229980469 - 30 -0.0 - 10 -182.59748840332031 - 20 -169.62997436523437 - 30 -0.0 - 10 -183.33499145507812 - 20 -169.21748352050781 - 30 -0.0 - 10 -184.08499145507812 - 20 -168.82247924804687 - 30 -0.0 - 10 -184.84498596191406 - 20 -168.44497680664062 - 30 -0.0 - 10 -185.614990234375 - 20 -168.08497619628906 - 30 -0.0 - 10 -186.39498901367187 - 20 -167.74247741699219 - 30 -0.0 - 10 -187.18498229980469 - 20 -167.41998291015625 - 30 -0.0 - 10 -187.9849853515625 - 20 -167.11747741699219 - 30 -0.0 - 10 -188.79249572753906 - 20 -166.83247375488281 - 30 -0.0 - 10 -189.6099853515625 - 20 -166.56747436523437 - 30 -0.0 - 10 -190.43748474121094 - 20 -166.31997680664062 - 30 -0.0 - 10 -191.26998901367187 - 20 -166.094970703125 - 30 -0.0 - 10 -192.11248779296875 - 20 -165.88998413085937 - 30 -0.0 - 10 -192.96498107910156 - 20 -165.70497131347656 - 30 -0.0 - 10 -193.82249450683594 - 20 -165.53997802734375 - 30 -0.0 - 10 -194.68748474121094 - 20 -165.39747619628906 - 30 -0.0 - 10 -195.55998229980469 - 20 -165.27497863769531 - 30 -0.0 - 10 -196.43748474121094 - 20 -165.17497253417969 - 30 -0.0 - 10 -197.32498168945313 - 20 -165.094970703125 - 30 -0.0 - 10 -198.21498107910156 - 20 -165.03997802734375 - 30 -0.0 - 10 -199.11248779296875 - 20 -165.00497436523437 - 30 -0.0 - 10 -200.01748657226562 - 20 -164.99247741699219 - 30 -0.0 - 10 -200.91998291015625 - 20 -165.00497436523437 - 30 -0.0 - 0 -LWPOLYLINE - 5 -61 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -102 - 70 -0 - 10 -185.10331726074219 - 20 -198.31785583496094 - 30 -0.0 - 10 -185.08499145507812 - 20 -198.46247863769531 - 30 -0.0 - 10 -185.02748107910156 - 20 -199.2249755859375 - 30 -0.0 - 10 -185.00749206542969 - 20 -199.99748229980469 - 30 -0.0 - 10 -185.02748107910156 - 20 -200.76997375488281 - 30 -0.0 - 10 -185.08499145507812 - 20 -201.532470703125 - 30 -0.0 - 10 -185.17999267578125 - 20 -202.282470703125 - 30 -0.0 - 10 -185.31248474121094 - 20 -203.01997375488281 - 30 -0.0 - 10 -185.47999572753906 - 20 -203.74748229980469 - 30 -0.0 - 10 -185.6824951171875 - 20 -204.45747375488281 - 30 -0.0 - 10 -185.91749572753906 - 20 -205.15498352050781 - 30 -0.0 - 10 -186.18748474121094 - 20 -205.83747863769531 - 30 -0.0 - 10 -186.48748779296875 - 20 -206.49996948242187 - 30 -0.0 - 10 -186.81748962402344 - 20 -207.14747619628906 - 30 -0.0 - 10 -187.17999267578125 - 20 -207.77497863769531 - 30 -0.0 - 10 -187.56999206542969 - 20 -208.38497924804687 - 30 -0.0 - 10 -187.98748779296875 - 20 -208.97247314453125 - 30 -0.0 - 10 -188.4324951171875 - 20 -209.53997802734375 - 30 -0.0 - 10 -188.90498352050781 - 20 -210.08247375488281 - 30 -0.0 - 10 -189.40248107910156 - 20 -210.60498046875 - 30 -0.0 - 10 -189.9224853515625 - 20 -211.0999755859375 - 30 -0.0 - 10 -190.46748352050781 - 20 -211.57247924804687 - 30 -0.0 - 10 -191.03498840332031 - 20 -212.01747131347656 - 30 -0.0 - 10 -191.62248229980469 - 20 -212.43498229980469 - 30 -0.0 - 10 -192.22998046875 - 20 -212.82498168945313 - 30 -0.0 - 10 -192.8599853515625 - 20 -213.18746948242187 - 30 -0.0 - 10 -193.50498962402344 - 20 -213.51747131347656 - 30 -0.0 - 10 -194.009033203125 - 20 -213.74676513671875 - 30 -0.0 - 10 -194.00900268554687 - 20 -234.47123718261719 - 30 -0.0 - 10 -193.82249450683594 - 20 -234.43997192382812 - 30 -0.0 - 10 -192.96498107910156 - 20 -234.27748107910156 - 30 -0.0 - 10 -192.114990234375 - 20 -234.09248352050781 - 30 -0.0 - 10 -191.27249145507812 - 20 -233.88497924804687 - 30 -0.0 - 10 -190.43748474121094 - 20 -233.65997314453125 - 30 -0.0 - 10 -189.6099853515625 - 20 -233.41497802734375 - 30 -0.0 - 10 -188.79249572753906 - 20 -233.14747619628906 - 30 -0.0 - 10 -187.9849853515625 - 20 -232.86497497558594 - 30 -0.0 - 10 -187.18498229980469 - 20 -232.55998229980469 - 30 -0.0 - 10 -186.39498901367187 - 20 -232.23747253417969 - 30 -0.0 - 10 -185.614990234375 - 20 -231.89497375488281 - 30 -0.0 - 10 -184.84498596191406 - 20 -231.53497314453125 - 30 -0.0 - 10 -184.08499145507812 - 20 -231.157470703125 - 30 -0.0 - 10 -183.33499145507812 - 20 -230.76248168945313 - 30 -0.0 - 10 -182.59748840332031 - 20 -230.3499755859375 - 30 -0.0 - 10 -181.8699951171875 - 20 -229.91998291015625 - 30 -0.0 - 10 -181.15498352050781 - 20 -229.47247314453125 - 30 -0.0 - 10 -180.44998168945312 - 20 -229.00997924804687 - 30 -0.0 - 10 -179.75749206542969 - 20 -228.52998352050781 - 30 -0.0 - 10 -179.07748413085937 - 20 -228.03497314453125 - 30 -0.0 - 10 -178.40998840332031 - 20 -227.52247619628906 - 30 -0.0 - 10 -177.75498962402344 - 20 -226.99497985839844 - 30 -0.0 - 10 -177.11248779296875 - 20 -226.45246887207031 - 30 -0.0 - 10 -176.4849853515625 - 20 -225.89497375488281 - 30 -0.0 - 10 -175.26998901367187 - 20 -224.73747253417969 - 30 -0.0 - 10 -174.1099853515625 - 20 -223.51997375488281 - 30 -0.0 - 10 -173.552490234375 - 20 -222.89247131347656 - 30 -0.0 - 10 -173.00999450683594 - 20 -222.25247192382812 - 30 -0.0 - 10 -172.48248291015625 - 20 -221.59747314453125 - 30 -0.0 - 10 -171.96998596191406 - 20 -220.92997741699219 - 30 -0.0 - 10 -171.47499084472656 - 20 -220.24996948242187 - 30 -0.0 - 10 -170.9949951171875 - 20 -219.55747985839844 - 30 -0.0 - 10 -170.52998352050781 - 20 -218.85247802734375 - 30 -0.0 - 10 -170.08248901367187 - 20 -218.13748168945312 - 30 -0.0 - 10 -169.65248107910156 - 20 -217.40997314453125 - 30 -0.0 - 10 -169.239990234375 - 20 -216.67247009277344 - 30 -0.0 - 10 -168.84498596191406 - 20 -215.92247009277344 - 30 -0.0 - 10 -168.46748352050781 - 20 -215.1624755859375 - 30 -0.0 - 10 -168.10748291015625 - 20 -214.39247131347656 - 30 -0.0 - 10 -167.76498413085937 - 20 -213.61247253417969 - 30 -0.0 - 10 -167.44248962402344 - 20 -212.82247924804687 - 30 -0.0 - 10 -167.13748168945312 - 20 -212.02247619628906 - 30 -0.0 - 10 -166.85249328613281 - 20 -211.21498107910156 - 30 -0.0 - 10 -166.58749389648437 - 20 -210.39747619628906 - 30 -0.0 - 10 -166.33998107910156 - 20 -209.56997680664062 - 30 -0.0 - 10 -166.114990234375 - 20 -208.73747253417969 - 30 -0.0 - 10 -165.90748596191406 - 20 -207.89497375488281 - 30 -0.0 - 10 -165.72248840332031 - 20 -207.04248046875 - 30 -0.0 - 10 -165.5574951171875 - 20 -206.18498229980469 - 30 -0.0 - 10 -165.41499328613281 - 20 -205.31997680664062 - 30 -0.0 - 10 -165.29249572753906 - 20 -204.44747924804687 - 30 -0.0 - 10 -165.18998718261719 - 20 -203.56997680664062 - 30 -0.0 - 10 -165.1099853515625 - 20 -202.68247985839844 - 30 -0.0 - 10 -165.05499267578125 - 20 -201.79248046875 - 30 -0.0 - 10 -165.01998901367188 - 20 -200.89497375488281 - 30 -0.0 - 10 -165.00749206542969 - 20 -199.98997497558594 - 30 -0.0 - 10 -165.01998901367188 - 20 -199.98997497558594 - 30 -0.0 - 10 -165.03248596191406 - 20 -199.08747863769531 - 30 -0.0 - 10 -165.06498718261719 - 20 -198.18997192382812 - 30 -0.0 - 10 -165.12248229980469 - 20 -197.29747009277344 - 30 -0.0 - 10 -165.19998168945312 - 20 -196.4124755859375 - 30 -0.0 - 10 -165.29998779296875 - 20 -195.532470703125 - 30 -0.0 - 10 -165.4224853515625 - 20 -194.65997314453125 - 30 -0.0 - 10 -165.56748962402344 - 20 -193.79498291015625 - 30 -0.0 - 10 -165.72999572753906 - 20 -192.93746948242187 - 30 -0.0 - 10 -165.91499328613281 - 20 -192.08747863769531 - 30 -0.0 - 10 -166.12248229980469 - 20 -191.24497985839844 - 30 -0.0 - 10 -166.34748840332031 - 20 -190.40997314453125 - 30 -0.0 - 10 -166.59248352050781 - 20 -189.58247375488281 - 30 -0.0 - 10 -166.8599853515625 - 20 -188.76498413085937 - 30 -0.0 - 10 -167.14248657226562 - 20 -187.95747375488281 - 30 -0.0 - 10 -167.14540100097656 - 20 -187.94984436035156 - 30 -0.0 - 10 -185.10331726074219 - 20 -198.31785583496094 - 30 -0.0 - 0 -LWPOLYLINE - 5 -62 -100 -AcDbEntity - 8 -0 - 62 --1 -420 -0 -370 -1 - 48 -1.0 - 6 -CONTINUOUS -100 -AcDbPolyline - 90 -101 - 70 -0 - 10 -232.88998413085937 - 20 -187.96247863769531 - 30 -0.0 - 10 -233.17498779296875 - 20 -188.77247619628906 - 30 -0.0 - 10 -233.43998718261719 - 20 -189.58998107910156 - 30 -0.0 - 10 -233.68748474121094 - 20 -190.41748046875 - 30 -0.0 - 10 -233.91249084472656 - 20 -191.25247192382812 - 30 -0.0 - 10 -234.11749267578125 - 20 -192.094970703125 - 30 -0.0 - 10 -234.302490234375 - 20 -192.94497680664062 - 30 -0.0 - 10 -234.46748352050781 - 20 -193.80497741699219 - 30 -0.0 - 10 -234.6099853515625 - 20 -194.66998291015625 - 30 -0.0 - 10 -234.73248291015625 - 20 -195.54248046875 - 30 -0.0 - 10 -234.83248901367187 - 20 -196.42247009277344 - 30 -0.0 - 10 -234.91249084472656 - 20 -197.30747985839844 - 30 -0.0 - 10 -234.96748352050781 - 20 -198.19998168945312 - 30 -0.0 - 10 -235.00248718261719 - 20 -199.09747314453125 - 30 -0.0 - 10 -235.01498413085937 - 20 -200.00247192382812 - 30 -0.0 - 10 -235.00248718261719 - 20 -200.89247131347656 - 30 -0.0 - 10 -234.96998596191406 - 20 -201.78997802734375 - 30 -0.0 - 10 -234.91249084472656 - 20 -202.68247985839844 - 30 -0.0 - 10 -234.83499145507812 - 20 -203.56747436523437 - 30 -0.0 - 10 -234.7349853515625 - 20 -204.44747924804687 - 30 -0.0 - 10 -234.61248779296875 - 20 -205.31997680664062 - 30 -0.0 - 10 -234.46748352050781 - 20 -206.18498229980469 - 30 -0.0 - 10 -234.30499267578125 - 20 -207.04248046875 - 30 -0.0 - 10 -234.11749267578125 - 20 -207.89247131347656 - 30 -0.0 - 10 -233.91249084472656 - 20 -208.73497009277344 - 30 -0.0 - 10 -233.68748474121094 - 20 -209.56997680664062 - 30 -0.0 - 10 -233.44248962402344 - 20 -210.39747619628906 - 30 -0.0 - 10 -233.17498779296875 - 20 -211.21498107910156 - 30 -0.0 - 10 -232.88998413085937 - 20 -212.02247619628906 - 30 -0.0 - 10 -232.58749389648437 - 20 -212.82247924804687 - 30 -0.0 - 10 -232.26498413085937 - 20 -213.61247253417969 - 30 -0.0 - 10 -231.9224853515625 - 20 -214.39247131347656 - 30 -0.0 - 10 -231.56248474121094 - 20 -215.1624755859375 - 30 -0.0 - 10 -231.18498229980469 - 20 -215.92247009277344 - 30 -0.0 - 10 -230.78999328613281 - 20 -216.67247009277344 - 30 -0.0 - 10 -230.37748718261719 - 20 -217.40997314453125 - 30 -0.0 - 10 -229.94749450683594 - 20 -218.13748168945312 - 30 -0.0 - 10 -229.49998474121094 - 20 -218.85247802734375 - 30 -0.0 - 10 -229.03749084472656 - 20 -219.55747985839844 - 30 -0.0 - 10 -228.55747985839844 - 20 -220.24996948242187 - 30 -0.0 - 10 -228.05998229980469 - 20 -220.92997741699219 - 30 -0.0 - 10 -227.54998779296875 - 20 -221.59747314453125 - 30 -0.0 - 10 -227.02249145507812 - 20 -222.25247192382812 - 30 -0.0 - 10 -226.47998046875 - 20 -222.89497375488281 - 30 -0.0 - 10 -225.9224853515625 - 20 -223.52247619628906 - 30 -0.0 - 10 -224.76248168945312 - 20 -224.73747253417969 - 30 -0.0 - 10 -223.5474853515625 - 20 -225.89747619628906 - 30 -0.0 - 10 -222.91748046875 - 20 -226.45497131347656 - 30 -0.0 - 10 -222.27748107910156 - 20 -226.99748229980469 - 30 -0.0 - 10 -221.62248229980469 - 20 -227.52497863769531 - 30 -0.0 - 10 -220.95498657226562 - 20 -228.0374755859375 - 30 -0.0 - 10 -220.27499389648437 - 20 -228.532470703125 - 30 -0.0 - 10 -219.58248901367188 - 20 -229.01248168945312 - 30 -0.0 - 10 -218.87748718261719 - 20 -229.47747802734375 - 30 -0.0 - 10 -218.15998840332031 - 20 -229.92497253417969 - 30 -0.0 - 10 -217.4324951171875 - 20 -230.35498046875 - 30 -0.0 - 10 -216.69499206542969 - 20 -230.76747131347656 - 30 -0.0 - 10 -215.94499206542969 - 20 -231.1624755859375 - 30 -0.0 - 10 -215.18498229980469 - 20 -231.53997802734375 - 30 -0.0 - 10 -214.41499328613281 - 20 -231.89997863769531 - 30 -0.0 - 10 -213.63499450683594 - 20 -232.24247741699219 - 30 -0.0 - 10 -212.84498596191406 - 20 -232.56497192382812 - 30 -0.0 - 10 -212.04498291015625 - 20 -232.86997985839844 - 30 -0.0 - 10 -211.2349853515625 - 20 -233.15498352050781 - 30 -0.0 - 10 -210.41748046875 - 20 -233.41998291015625 - 30 -0.0 - 10 -209.58998107910156 - 20 -233.66748046875 - 30 -0.0 - 10 -208.75498962402344 - 20 -233.89247131347656 - 30 -0.0 - 10 -207.91249084472656 - 20 -234.0999755859375 - 30 -0.0 - 10 -207.06248474121094 - 20 -234.28497314453125 - 30 -0.0 - 10 -206.20248413085937 - 20 -234.44998168945312 - 30 -0.0 - 10 -206.00898742675781 - 20 -234.48185729980469 - 30 -0.0 - 10 -206.00900268554687 - 20 -213.74650573730469 - 30 -0.0 - 10 -206.51248168945313 - 20 -213.51747131347656 - 30 -0.0 - 10 -207.15998840332031 - 20 -213.18746948242187 - 30 -0.0 - 10 -207.78749084472656 - 20 -212.82498168945313 - 30 -0.0 - 10 -208.39498901367187 - 20 -212.43498229980469 - 30 -0.0 - 10 -208.9849853515625 - 20 -212.01747131347656 - 30 -0.0 - 10 -209.54998779296875 - 20 -211.57247924804687 - 30 -0.0 - 10 -210.09498596191406 - 20 -211.0999755859375 - 30 -0.0 - 10 -210.614990234375 - 20 -210.60498046875 - 30 -0.0 - 10 -211.11248779296875 - 20 -210.08247375488281 - 30 -0.0 - 10 -211.58499145507812 - 20 -209.53997802734375 - 30 -0.0 - 10 -212.02998352050781 - 20 -208.97247314453125 - 30 -0.0 - 10 -212.44749450683594 - 20 -208.38497924804687 - 30 -0.0 - 10 -212.83749389648437 - 20 -207.77497863769531 - 30 -0.0 - 10 -213.19998168945312 - 20 -207.14747619628906 - 30 -0.0 - 10 -213.52998352050781 - 20 -206.49996948242187 - 30 -0.0 - 10 -213.82998657226562 - 20 -205.83747863769531 - 30 -0.0 - 10 -214.09999084472656 - 20 -205.15498352050781 - 30 -0.0 - 10 -214.33499145507812 - 20 -204.45747375488281 - 30 -0.0 - 10 -214.53749084472656 - 20 -203.74748229980469 - 30 -0.0 - 10 -214.70498657226562 - 20 -203.01997375488281 - 30 -0.0 - 10 -214.83749389648437 - 20 -202.282470703125 - 30 -0.0 - 10 -214.9324951171875 - 20 -201.532470703125 - 30 -0.0 - 10 -214.989990234375 - 20 -200.76997375488281 - 30 -0.0 - 10 -215.00999450683594 - 20 -199.99748229980469 - 30 -0.0 - 10 -214.989990234375 - 20 -199.2249755859375 - 30 -0.0 - 10 -214.9324951171875 - 20 -198.46247863769531 - 30 -0.0 - 10 -214.9154052734375 - 20 -198.32762145996094 - 30 -0.0 - 10 -232.8861083984375 - 20 -187.95222473144531 - 30 -0.0 - 10 -232.88998413085937 - 20 -187.96247863769531 - 30 -0.0 - 0 -ENDSEC - 0 -SECTION - 2 -OBJECTS - 0 -DICTIONARY - 5 -C -100 -AcDbDictionary -280 -0 -281 -1 - 3 -ACAD_GROUP -350 -D - 3 -ACAD_LAYOUT -350 -1A - 3 -ACAD_MLINESTYLE -350 -17 - 3 -ACAD_PLOTSETTINGS -350 -19 - 3 -ACAD_PLOTSTYLENAME -350 -E - 3 -AcDbVariableDictionary -350 -63 - 0 -DICTIONARY - 5 -D -100 -AcDbDictionary -280 -0 -281 -1 - 0 -ACDBDICTIONARYWDFLT - 5 -E -100 -AcDbDictionary -281 -1 - 3 -Normal -350 -F -100 -AcDbDictionaryWithDefault -340 -F - 0 -ACDBPLACEHOLDER - 5 -F - 0 -DICTIONARY - 5 -17 -100 -AcDbDictionary -280 -0 -281 -1 - 3 -Standard -350 -18 - 0 -MLINESTYLE - 5 -18 -100 -AcDbMlineStyle - 2 -STANDARD - 70 -0 - 3 - - 62 -256 - 51 -90.0 - 52 -90.0 - 71 -2 - 49 -0.5 - 62 -256 - 6 -BYLAYER - 49 --0.5 - 62 -256 - 6 -BYLAYER - 0 -DICTIONARY - 5 -19 -100 -AcDbDictionary -280 -0 -281 -1 - 0 -DICTIONARY - 5 -1A -100 -AcDbDictionary -281 -1 - 3 -Layout1 -350 -1E - 3 -Layout2 -350 -26 - 3 -Model -350 -22 - 0 -LAYOUT - 5 -1E -100 -AcDbPlotSettings - 1 - - 2 -none_device - 4 - - 6 - - 40 -0.0 - 41 -0.0 - 42 -0.0 - 43 -0.0 - 44 -0.0 - 45 -0.0 - 46 -0.0 - 47 -0.0 - 48 -0.0 - 49 -0.0 -140 -0.0 -141 -0.0 -142 -1.0 -143 -1.0 - 70 -688 - 72 -0 - 73 -0 - 74 -5 - 7 - - 75 -16 -147 -1.0 -148 -0.0 -149 -0.0 -100 -AcDbLayout - 1 -Layout1 - 70 -1 - 71 -1 - 10 -0.0 - 20 -0.0 - 11 -420.0 - 21 -297.0 - 12 -0.0 - 22 -0.0 - 32 -0.0 - 14 -100000000000000000000.0 - 24 -100000000000000000000.0 - 34 -100000000000000000000.0 - 15 --100000000000000000000.0 - 25 --100000000000000000000.0 - 35 --100000000000000000000.0 -146 -0.0 - 13 -0.0 - 23 -0.0 - 33 -0.0 - 16 -1.0 - 26 -0.0 - 36 -0.0 - 17 -0.0 - 27 -1.0 - 37 -0.0 - 76 -0 -330 -1B - 0 -LAYOUT - 5 -22 -100 -AcDbPlotSettings - 1 - - 2 -none_device - 4 - - 6 - - 40 -0.0 - 41 -0.0 - 42 -0.0 - 43 -0.0 - 44 -0.0 - 45 -0.0 - 46 -0.0 - 47 -0.0 - 48 -0.0 - 49 -0.0 -140 -0.0 -141 -0.0 -142 -1.0 -143 -1.0 - 70 -1712 - 72 -0 - 73 -0 - 74 -0 - 7 - - 75 -0 -147 -1.0 -148 -0.0 -149 -0.0 -100 -AcDbLayout - 1 -Model - 70 -1 - 71 -0 - 10 -0.0 - 20 -0.0 - 11 -12.0 - 21 -9.0 - 12 -0.0 - 22 -0.0 - 32 -0.0 - 14 -0.0 - 24 -0.0 - 34 -0.0 - 15 -0.0 - 25 -0.0 - 35 -0.0 -146 -0.0 - 13 -0.0 - 23 -0.0 - 33 -0.0 - 16 -1.0 - 26 -0.0 - 36 -0.0 - 17 -0.0 - 27 -1.0 - 37 -0.0 - 76 -0 -330 -1F - 0 -LAYOUT - 5 -26 -100 -AcDbPlotSettings - 1 - - 2 -none_device - 4 - - 6 - - 40 -0.0 - 41 -0.0 - 42 -0.0 - 43 -0.0 - 44 -0.0 - 45 -0.0 - 46 -0.0 - 47 -0.0 - 48 -0.0 - 49 -0.0 -140 -0.0 -141 -0.0 -142 -1.0 -143 -1.0 - 70 -688 - 72 -0 - 73 -0 - 74 -5 - 7 - - 75 -16 -147 -1.0 -148 -0.0 -149 -0.0 -100 -AcDbLayout - 1 -Layout2 - 70 -1 - 71 -2 - 10 -0.0 - 20 -0.0 - 11 -12.0 - 21 -9.0 - 12 -0.0 - 22 -0.0 - 32 -0.0 - 14 -0.0 - 24 -0.0 - 34 -0.0 - 15 -0.0 - 25 -0.0 - 35 -0.0 -146 -0.0 - 13 -0.0 - 23 -0.0 - 33 -0.0 - 16 -1.0 - 26 -0.0 - 36 -0.0 - 17 -0.0 - 27 -1.0 - 37 -0.0 - 76 -0 -330 -23 - 0 -DICTIONARY - 5 -63 -100 -AcDbDictionary -281 -1 - 3 -DIMASSOC -350 -65 - 3 -HIDETEXT -350 -64 - 0 -DICTIONARYVAR - 5 -64 -100 -DictionaryVariables -280 -0 - 1 -2 - 0 -DICTIONARYVAR - 5 -65 -100 -DictionaryVariables -280 -0 - 1 -1 - 0 -ENDSEC - 0 -EOF diff --git a/莱洛三角切割/wheel.lcp b/莱洛三角切割/wheel.lcp deleted file mode 100644 index d97570e3acef7dad0088a0f99280a8b33f4c6c3a..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6047 zcmbW5dwA2;8OM|UL@6>T(mH_>TH3VX+BT^`3!$aow&?}hrgun7L1;?TD*^(QQIL26 z(M%YZC@|^t&r{XU|Hip#JZjK~AL`Hl<|qBP3_jD)?|bCjusqzj5e3a{_0usd z7zM==b|<{cr$Z?q+#a+*DIpXdSOF!HHn#^iLMfxytpau(S^=#9Ygh;737bMf@CLmK z2**VnCvAe9LJ7^aO(b@6ayPR`Oysyl{G*$thGXG1rh1?fWcS zjiPC5;&wS2(fpGY3f{r#% z$1^SAbx^=5?$%QR!cOMkps*33dI?bD2%ASmS6`i%SG$^#j?6 ziO7Z0PEdHbW@cw06yY^pfa^-W969wsA+8FW-w;NK5)=?E;yg^73nFr8 zt|28lE-M$l-e_pX6LQ~}2<4|EEI6}S2W1ko`J;dzew!yp5h{ydICMcad<6&wvLb(I+NUBQV zu{OuyzR!~RXzyekuOn=7#$wu0!aKubv96OgBOi-FZw0;9`(n`7z&N3~hLq@^`=asv z6Zz1Tyg3nf5|oQub=dMvo`f-)K{z~|va`}=cqV0cmR{ikR-c|AM?TX|z%#<;3?V{z ziIJ@$PCISX$f3E0l;}TO;!qu52TfLXJPsXM%0qlC9tZcB37hg@#YpNKN**bisoi0H8A1O-^1*N@&>OUpp z$sf_?@QP%dbI@yKcQVdzYK2m{Ed__K5e_XjqH1j$ZJJEDJe3fdYes z@F&Z?Q1GujP#`P}=!Qg)TC zOyD44@s?KXEhCJ%-ik#(pv|fEO#69y)y`~#b`Rr(<{DC>tyydE+Pqw7ZWP>$R|$&! zfz`+##`+cT=Ji3Ca+UQfZ2I0}XK1093ZJK~m9RE!9aNij1l3D`8b{cukwbG0DbZ7V zn(?>(WN12%H{nP*``_66nsCg{{`cOMCVV}Q{cl@KGt6VzSs&_b!Lb^`?<-nyWq^;y zO>aYbJ>kK1ZJ1R?FYmXl_;M5DL~U+G*H744?`UqpoLWL?t|29QWkL<2kH$ii#0`}xoX9MF1RFM$0E zf^~l(TptkJ8y6zbLkLtag4<27&niO4T7rK}F$M|Jr%gS`V$|>=Jl45j=ai-M13LEj4gHx)NGlpazDKgy5lCxVQ5Q zNw{SxTww&Ke<`}x-vg~-XB{V9&NNOgL-6=Aj$B@jz$10g4s_gu?(<8b-FEgKxLXN* z{t`q*lrwUD32bcy_o-qSKO_VU#Rw)Ri0OO;@$EDdp^Hgo@rqJEP2YFirMnqJyCO{60H4mq&C_Qrb)Hv>eHouY)Nya zq72vPN{yX8Jx{96aKMcA7RoQ!HeV`Jmy;p2>W$8n>J9%U6K0`j*9Y7mq440#SqSVW z*j#{BR6(#Un|nwwmgUGw37?&dj;kE;MqAWs(staEhb~PMwtm+yv-PaWHRIDz)y3i2h?AHPPX$37ZO4xY z;;;k#VuU$cViP$#1z~F=2#NUn2tqXOaRycwW#m~$5W=$i1W; zu~WG&3e@u;K}gncoghRUzJ40J24(FD5QNYJ8>VwzlzuQs@J6TL?2Z}ChvnfOHDUYmxl2$N{R)6mmP=(#Z!!M0T9 z^YB!3#NW+;QB&dkj1d0(6nOT`VnFj0mi=t8Km%NN%n^rTfbI_j=L7@HPo{}Zmk9rI zaRjRqSyVg}V_YHv*9hiM6VUxGPtd+MfzlVJT$KQCGta$!Vgi$=608^WTn7pS9B{tJ-4X4^bB_Dv zQ<@OT|6@}}%;O2xYYudza=TS8aR461X>Son@|Hs$l9zL-$0lZ14>GcdlZvAi8Jfov zM9!`(9=}+HDhSJJE>K8BtW*_^Si34C``%SjSU#+hQZrm`km3uv8l)U;Nexn<=F@g5 z*{)@FDPq^(>!qxNo%K@a?(ljk{hvR+QWk@4^h#MC-kmFC!FYzPkR>GUZTC3Vl6sSG zV3`?tx68s4xBXo##eqvpVHU+H-Uw`>Ty1VAghxPdUo2*yWfKgJE{5lIf{$u< zK1x^=Rs`ENLJ{F9(M-i_h}vGoi;3EB#jA?ig4LH7(Uc9>8CkSx?@p_1+}68FWh-w# zSSp*lH<~YQqTPG;lnq`0x0TB)!F6xByd>3+CEUM(FTRmjW6J+4w- zKc0$8c_F#CSIR4@<7XTZmzLdEDX+1fuL$B|YyUSNiL1^PRwXY#F`{0F!bZIyt1ngJ R<72FX{y(q6l@Wt=`yWjiqT&Dm