├── BOM表.xlsx ├── DengFOC 莱洛三角形程序 └── lailuo │ ├── Command.cpp │ ├── Command.h │ ├── Kalman.cpp │ ├── Kalman.h │ ├── i2c.ino │ ├── lailuo.ino │ └── rewrite.cpp ├── LICENSE ├── README.md ├── pic ├── effect.gif ├── effect2.gif ├── jxbz1.jpg ├── jxbz2.jpg ├── jxbz3.jpg ├── jxbz4.jpg ├── jxbz5.jpg ├── jxbz6.jpg ├── jxbz7.jpg ├── jxk.png ├── ts1.png ├── ts10.png ├── ts2.png ├── ts3.png ├── ts5.png ├── ts6.png ├── ts7.png ├── ts8.png ├── ts9.jpg ├── xc.jpg └── 图片2.png ├── 机械结构 ├── 3D打印版 │ ├── centre_pan.stl │ ├── lailuo_base2_19.stl │ ├── lailuo_base_24.stl │ └── triangle_bar_4.stl └── 木材版 │ ├── ban1.dxf │ ├── ban2.dxf │ ├── lun1.dxf │ └── triangle_bar_4.stl └── 调试上位机.zip /BOM表.xlsx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/BOM表.xlsx -------------------------------------------------------------------------------- /DengFOC 莱洛三角形程序/lailuo/Command.cpp: -------------------------------------------------------------------------------- 1 | #include "Command.h" 2 | 3 | void Command::run(char* str){ 4 | for(int i=0; i < call_count; i++){ 5 | if(isSentinel(call_ids[i],str)){ // case : call_ids = "T2" str = "T215.15" 6 | call_list[i](str+strlen(call_ids[i])); // get 15.15 input function 7 | break; 8 | } 9 | } 10 | } 11 | void Command::add(char* id, CommandCallback onCommand){ 12 | call_list[call_count] = onCommand; 13 | call_ids[call_count] = id; 14 | call_count++; 15 | } 16 | void Command::scalar(float* value, char* user_cmd){ 17 | *value = atof(user_cmd); 18 | } 19 | bool Command::isSentinel(char* ch,char* str) 20 | { 21 | char s[strlen(ch)+1]; 22 | strncpy(s,str,strlen(ch)); 23 | s[strlen(ch)] = '\0'; //strncpy need add end '\0' 24 | if(strcmp(ch, s) == 0) 25 | return true; 26 | else 27 | return false; 28 | } 29 | -------------------------------------------------------------------------------- /DengFOC 莱洛三角形程序/lailuo/Command.h: -------------------------------------------------------------------------------- 1 | #include 2 | // callback function pointer definiton 3 | typedef void (* CommandCallback)(char*); //!< command callback function pointer 4 | class Command 5 | { 6 | public: 7 | void add(char* id , CommandCallback onCommand); 8 | void run(char* str); 9 | void scalar(float* value, char* user_cmd); 10 | bool isSentinel(char* ch,char* str); 11 | private: 12 | // Subscribed command callback variables 13 | CommandCallback call_list[20];//!< array of command callback pointers - 20 is an arbitrary number 14 | char* call_ids[20]; //!< added callback commands 15 | int call_count;//!< number callbacks that are subscribed 16 | 17 | }; 18 | -------------------------------------------------------------------------------- /DengFOC 莱洛三角形程序/lailuo/Kalman.cpp: -------------------------------------------------------------------------------- 1 | /* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved. 2 | 3 | This software may be distributed and modified under the terms of the GNU 4 | General Public License version 2 (GPL2) as published by the Free Software 5 | Foundation and appearing in the file GPL2.TXT included in the packaging of 6 | this file. Please note that GPL2 Section 2[b] requires that all works based 7 | on this software must also be made publicly available under the terms of 8 | the GPL2 ("Copyleft"). 9 | 10 | Contact information 11 | ------------------- 12 | 13 | Kristian Lauszus, TKJ Electronics 14 | Web : http://www.tkjelectronics.com 15 | e-mail : kristianl@tkjelectronics.com 16 | */ 17 | 18 | #include "Kalman.h" 19 | 20 | Kalman::Kalman() { 21 | /* We will set the variables like so, these can also be tuned by the user */ 22 | Q_angle = 0.001f; 23 | Q_bias = 0.003f; 24 | R_measure = 0.03f; 25 | 26 | angle = 0.0f; // Reset the angle 27 | bias = 0.0f; // Reset bias 28 | 29 | P[0][0] = 0.0f; // Since we assume that the bias is 0 and we know the starting angle (use setAngle), the error covariance matrix is set like so - see: http://en.wikipedia.org/wiki/Kalman_filter#Example_application.2C_technical 30 | P[0][1] = 0.0f; 31 | P[1][0] = 0.0f; 32 | P[1][1] = 0.0f; 33 | }; 34 | 35 | // The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds 36 | float Kalman::getAngle(float newAngle, float newRate, float dt) { 37 | // KasBot V2 - Kalman filter module - http://www.x-firm.com/?page_id=145 38 | // Modified by Kristian Lauszus 39 | // See my blog post for more information: http://blog.tkjelectronics.dk/2012/09/a-practical-approach-to-kalman-filter-and-how-to-implement-it 40 | 41 | // Discrete Kalman filter time update equations - Time Update ("Predict") 42 | // Update xhat - Project the state ahead 43 | /* Step 1 */ 44 | rate = newRate - bias; 45 | angle += dt * rate; 46 | 47 | // Update estimation error covariance - Project the error covariance ahead 48 | /* Step 2 */ 49 | P[0][0] += dt * (dt*P[1][1] - P[0][1] - P[1][0] + Q_angle); 50 | P[0][1] -= dt * P[1][1]; 51 | P[1][0] -= dt * P[1][1]; 52 | P[1][1] += Q_bias * dt; 53 | 54 | // Discrete Kalman filter measurement update equations - Measurement Update ("Correct") 55 | // Calculate Kalman gain - Compute the Kalman gain 56 | /* Step 4 */ 57 | float S = P[0][0] + R_measure; // Estimate error 58 | /* Step 5 */ 59 | float K[2]; // Kalman gain - This is a 2x1 vector 60 | K[0] = P[0][0] / S; 61 | K[1] = P[1][0] / S; 62 | 63 | // Calculate angle and bias - Update estimate with measurement zk (newAngle) 64 | /* Step 3 */ 65 | float y = newAngle - angle; // Angle difference 66 | /* Step 6 */ 67 | angle += K[0] * y; 68 | bias += K[1] * y; 69 | 70 | // Calculate estimation error covariance - Update the error covariance 71 | /* Step 7 */ 72 | float P00_temp = P[0][0]; 73 | float P01_temp = P[0][1]; 74 | 75 | P[0][0] -= K[0] * P00_temp; 76 | P[0][1] -= K[0] * P01_temp; 77 | P[1][0] -= K[1] * P00_temp; 78 | P[1][1] -= K[1] * P01_temp; 79 | 80 | return angle; 81 | }; 82 | 83 | void Kalman::setAngle(float angle) { this->angle = angle; }; // Used to set angle, this should be set as the starting angle 84 | float Kalman::getRate() { return this->rate; }; // Return the unbiased rate 85 | 86 | /* These are used to tune the Kalman filter */ 87 | void Kalman::setQangle(float Q_angle) { this->Q_angle = Q_angle; }; 88 | void Kalman::setQbias(float Q_bias) { this->Q_bias = Q_bias; }; 89 | void Kalman::setRmeasure(float R_measure) { this->R_measure = R_measure; }; 90 | 91 | float Kalman::getQangle() { return this->Q_angle; }; 92 | float Kalman::getQbias() { return this->Q_bias; }; 93 | float Kalman::getRmeasure() { return this->R_measure; }; 94 | -------------------------------------------------------------------------------- /DengFOC 莱洛三角形程序/lailuo/Kalman.h: -------------------------------------------------------------------------------- 1 | /* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved. 2 | 3 | This software may be distributed and modified under the terms of the GNU 4 | General Public License version 2 (GPL2) as published by the Free Software 5 | Foundation and appearing in the file GPL2.TXT included in the packaging of 6 | this file. Please note that GPL2 Section 2[b] requires that all works based 7 | on this software must also be made publicly available under the terms of 8 | the GPL2 ("Copyleft"). 9 | 10 | Contact information 11 | ------------------- 12 | 13 | Kristian Lauszus, TKJ Electronics 14 | Web : http://www.tkjelectronics.com 15 | e-mail : kristianl@tkjelectronics.com 16 | */ 17 | 18 | #ifndef _Kalman_h_ 19 | #define _Kalman_h_ 20 | 21 | class Kalman { 22 | public: 23 | Kalman(); 24 | 25 | // The angle should be in degrees and the rate should be in degrees per second and the delta time in seconds 26 | float getAngle(float newAngle, float newRate, float dt); 27 | 28 | void setAngle(float angle); // Used to set angle, this should be set as the starting angle 29 | float getRate(); // Return the unbiased rate 30 | 31 | /* These are used to tune the Kalman filter */ 32 | void setQangle(float Q_angle); 33 | /** 34 | * setQbias(float Q_bias) 35 | * Default value (0.003f) is in Kalman.cpp. 36 | * Raise this to follow input more closely, 37 | * lower this to smooth result of kalman filter. 38 | */ 39 | void setQbias(float Q_bias); 40 | void setRmeasure(float R_measure); 41 | 42 | float getQangle(); 43 | float getQbias(); 44 | float getRmeasure(); 45 | 46 | private: 47 | /* Kalman filter variables */ 48 | float Q_angle; // Process noise variance for the accelerometer 49 | float Q_bias; // Process noise variance for the gyro bias 50 | float R_measure; // Measurement noise variance - this is actually the variance of the measurement noise 51 | 52 | float angle; // The angle calculated by the Kalman filter - part of the 2x1 state vector 53 | float bias; // The gyro bias calculated by the Kalman filter - part of the 2x1 state vector 54 | float rate; // Unbiased rate calculated from the rate and the calculated bias - you have to call getAngle to update the rate 55 | 56 | float P[2][2]; // Error covariance matrix - This is a 2x2 matrix 57 | }; 58 | 59 | #endif 60 | -------------------------------------------------------------------------------- /DengFOC 莱洛三角形程序/lailuo/i2c.ino: -------------------------------------------------------------------------------- 1 | /* Copyright (C) 2012 Kristian Lauszus, TKJ Electronics. All rights reserved. 2 | 3 | This software may be distributed and modified under the terms of the GNU 4 | General Public License version 2 (GPL2) as published by the Free Software 5 | Foundation and appearing in the file GPL2.TXT included in the packaging of 6 | this file. Please note that GPL2 Section 2[b] requires that all works based 7 | on this software must also be made publicly available under the terms of 8 | the GPL2 ("Copyleft"). 9 | 10 | Contact information 11 | ------------------- 12 | 13 | Kristian Lauszus, TKJ Electronics 14 | Web : http://www.tkjelectronics.com 15 | e-mail : kristianl@tkjelectronics.com 16 | */ 17 | 18 | const uint8_t IMUAddress = 0x68; // AD0 is logic low on the PCB 19 | const uint16_t I2C_TIMEOUT = 1000; // Used to check for errors in I2C communication 20 | 21 | uint8_t i2cWrite(uint8_t registerAddress, uint8_t data, bool sendStop) { 22 | return i2cWrite(registerAddress, &data, 1, sendStop); // Returns 0 on success 23 | } 24 | 25 | uint8_t i2cWrite(uint8_t registerAddress, uint8_t *data, uint8_t length, bool sendStop) { 26 | Wire.beginTransmission(IMUAddress); 27 | Wire.write(registerAddress); 28 | Wire.write(data, length); 29 | uint8_t rcode = Wire.endTransmission(sendStop); // Returns 0 on success 30 | if (rcode) { 31 | Serial.print(F("i2cWrite failed: ")); 32 | Serial.println(rcode); 33 | } 34 | return rcode; // See: http://arduino.cc/en/Reference/WireEndTransmission 35 | } 36 | 37 | uint8_t i2cRead(uint8_t registerAddress, uint8_t *data, uint8_t nbytes) { 38 | uint32_t timeOutTimer; 39 | Wire.beginTransmission(IMUAddress); 40 | Wire.write(registerAddress); 41 | uint8_t rcode = Wire.endTransmission(false); // Don't release the bus 42 | if (rcode) { 43 | Serial.print(F("i2cRead failed: ")); 44 | Serial.println(rcode); 45 | return rcode; // See: http://arduino.cc/en/Reference/WireEndTransmission 46 | } 47 | Wire.requestFrom(IMUAddress, nbytes, (uint8_t)true); // Send a repeated start and then release the bus after reading 48 | for (uint8_t i = 0; i < nbytes; i++) { 49 | if (Wire.available()) 50 | data[i] = Wire.read(); 51 | else { 52 | timeOutTimer = micros(); 53 | while (((micros() - timeOutTimer) < I2C_TIMEOUT) && !Wire.available()); 54 | if (Wire.available()) 55 | data[i] = Wire.read(); 56 | else { 57 | Serial.println(F("i2cRead timeout")); 58 | return 5; // This error value is not already taken by endTransmission 59 | } 60 | } 61 | } 62 | return 0; // Success 63 | } 64 | -------------------------------------------------------------------------------- /DengFOC 莱洛三角形程序/lailuo/lailuo.ino: -------------------------------------------------------------------------------- 1 | /** 2 | arduino开发环境-灯哥开源FOChttps://gitee.com/ream_d/Deng-s-foc-controller,并安装Kalman。 3 | FOC引脚32, 33, 25, 22 22为enable 4 | AS5600霍尔传感器 SDA-23 SCL-5 MPU6050六轴传感器 SDA-19 SCL-18 5 | 本程序有两种平衡方式, FLAG_V为1时使用电压控制,为0时候速度控制。电压控制时LQR参数使用K1和K2,速度控制时LQR参数使用K3和K4 6 | 在wifi上位机窗口中输入:TA+角度,就可以修改平衡角度 7 | 比如让平衡角度为90度,则输入:TA90,并且会存入eeprom的位置0中 注:wifi发送命令不能过快,因为每次都会保存进eeprom 8 | 在使用自己的电机时,请一定记得修改默认极对数,即 BLDCMotor(5) 中的值,设置为自己的极对数数字,磁铁数量/2 9 | 程序默认设置的供电电压为 12V,用其他电压供电请记得修改 voltage_power_supply , voltage_limit 变量中的值 10 | 默认PID针对的电机是 GB2204 ,使用自己的电机需要修改PID参数,才能实现更好效果 11 | */ 12 | #include 13 | #include "Command.h" 14 | #include 15 | #include //引用以使用异步UDP 16 | #include "Kalman.h" // Source: https://github.com/TKJElectronics/KalmanFilter 17 | #include "EEPROM.h" 18 | Kalman kalmanZ; 19 | #define gyroZ_OFF -0.19 20 | #define FLAG_V 0 21 | /* ----IMU Data---- */ 22 | 23 | double accX, accY, accZ; 24 | double gyroX, gyroY, gyroZ; 25 | int16_t tempRaw; 26 | bool stable = 0; 27 | uint32_t last_unstable_time; 28 | 29 | double gyroZangle; // Angle calculate using the gyro only 30 | double compAngleZ; // Calculated angle using a complementary filter 31 | double kalAngleZ; // Calculated angle using a Kalman filter 32 | 33 | uint32_t timer; 34 | uint8_t i2cData[14]; // Buffer for I2C data 35 | /* ----FOC Data---- */ 36 | 37 | // driver instance 38 | double acc2rotation(double x, double y); 39 | float constrainAngle(float x); 40 | const char *ssid = "esp32_lailuo"; 41 | const char *password = "qwe12345"; 42 | 43 | bool wifi_flag = 0; 44 | AsyncUDP udp; //创建UDP对象 45 | unsigned int localUdpPort = 2333; //本地端口号 46 | void wifi_print(char * s,double num); 47 | 48 | MagneticSensorI2C sensor = MagneticSensorI2C(AS5600_I2C); 49 | TwoWire I2Ctwo = TwoWire(1); 50 | LowPassFilter lpf_throttle{0.00}; 51 | 52 | //倒立摆参数 53 | float LQR_K1_1 = 4; //摇摆到平衡 54 | float LQR_K1_2 = 1.5; // 55 | float LQR_K1_3 = 0.30; // 56 | 57 | float LQR_K2_1 = 3.49; //平衡态 58 | float LQR_K2_2 = 0.26; // 59 | float LQR_K2_3 = 0.15; // 60 | 61 | float LQR_K3_1 = 10; //摇摆到平衡 62 | float LQR_K3_2 = 1.7; // 63 | float LQR_K3_3 = 1.75; // 64 | 65 | float LQR_K4_1 = 2.4; //摇摆到平衡 66 | float LQR_K4_2 = 1.5; // 67 | float LQR_K4_3 = 1.42; // 68 | 69 | //电机参数 70 | BLDCMotor motor = BLDCMotor(7); 71 | BLDCDriver3PWM driver = BLDCDriver3PWM(32, 33, 25, 22); 72 | float target_velocity = 0; 73 | float target_angle = 90.7; 74 | float target_voltage = 0; 75 | float swing_up_voltage = 1.8; 76 | float swing_up_angle = 15; 77 | float v_i_1 = 11; // 非自稳状态 78 | float v_p_1 = 0.56; // 非自稳状态 79 | float v_i_2 = 9; // 自稳状态 80 | float v_p_2 = 0.24; // 自稳状态 81 | //命令设置 82 | Command comm; 83 | bool Motor_enable_flag = 0; 84 | void do_TA(char* cmd) { comm.scalar(&target_angle, cmd);EEPROM.writeFloat(0, target_angle); } 85 | void do_SV(char* cmd) { comm.scalar(&swing_up_voltage, cmd); EEPROM.writeFloat(4, swing_up_voltage); } 86 | void do_SA(char* cmd) { comm.scalar(&swing_up_angle, cmd);EEPROM.writeFloat(8, swing_up_angle); } 87 | 88 | void do_START(char* cmd) { wifi_flag = !wifi_flag; } 89 | void do_MOTOR(char* cmd) 90 | { 91 | if(Motor_enable_flag) 92 | digitalWrite(22,HIGH); 93 | else 94 | digitalWrite(22,LOW); 95 | Motor_enable_flag = !Motor_enable_flag; 96 | } 97 | #if FLAG_V 98 | void do_K11(char* cmd) { comm.scalar(&LQR_K1_1, cmd); } 99 | void do_K12(char* cmd) { comm.scalar(&LQR_K1_2, cmd); } 100 | void do_K13(char* cmd) { comm.scalar(&LQR_K1_3, cmd); } 101 | void do_K21(char* cmd) { comm.scalar(&LQR_K2_1, cmd); } 102 | void do_K22(char* cmd) { comm.scalar(&LQR_K2_2, cmd); } 103 | void do_K23(char* cmd) { comm.scalar(&LQR_K2_3, cmd); } 104 | #else 105 | void do_vp1(char* cmd) { comm.scalar(&v_p_1, cmd); EEPROM.writeFloat(12, v_p_1);} 106 | void do_vi1(char* cmd) { comm.scalar(&v_i_1, cmd);EEPROM.writeFloat(16, v_p_1); } 107 | void do_vp2(char* cmd) { comm.scalar(&v_p_2, cmd); EEPROM.writeFloat(20, v_p_2);} 108 | void do_vi2(char* cmd) { comm.scalar(&v_i_2, cmd);EEPROM.writeFloat(24, v_i_2); } 109 | void do_tv(char* cmd) { comm.scalar(&target_velocity, cmd); } 110 | void do_K31(char* cmd) { comm.scalar(&LQR_K3_1, cmd); } 111 | void do_K32(char* cmd) { comm.scalar(&LQR_K3_2, cmd); } 112 | void do_K33(char* cmd) { comm.scalar(&LQR_K3_3, cmd); } 113 | void do_K41(char* cmd) { comm.scalar(&LQR_K4_1, cmd); } 114 | void do_K42(char* cmd) { comm.scalar(&LQR_K4_2, cmd); } 115 | void do_K43(char* cmd) { comm.scalar(&LQR_K4_3, cmd); } 116 | #endif 117 | 118 | 119 | void onPacketCallBack(AsyncUDPPacket packet) 120 | { 121 | char* da; 122 | da= (char*)(packet.data()); 123 | Serial.println(da); 124 | comm.run(da); 125 | EEPROM.commit(); 126 | // packet.print("reply data"); 127 | } 128 | // instantiate the commander 129 | void setup() { 130 | Serial.begin(115200); 131 | if (!EEPROM.begin(1000)) { 132 | Serial.println("Failed to initialise EEPROM"); 133 | Serial.println("Restarting..."); 134 | delay(1000); 135 | ESP.restart(); 136 | } 137 | 138 | //命令设置 139 | comm.add("TA",do_TA); 140 | comm.add("START",do_START); 141 | comm.add("MOTOR",do_MOTOR); 142 | comm.add("SV",do_SV); 143 | comm.add("SA",do_SA); 144 | target_angle = EEPROM.readFloat(0); 145 | swing_up_voltage = EEPROM.readFloat(4); 146 | swing_up_angle = EEPROM.readFloat(8); 147 | #if FLAG_V 148 | comm.add("K11",do_K11); 149 | comm.add("K12",do_K12); 150 | comm.add("K13",do_K13); 151 | comm.add("K21",do_K21); 152 | comm.add("K22",do_K22); 153 | comm.add("K23",do_K23); 154 | #else 155 | comm.add("VP1",do_vp1); 156 | comm.add("VI1",do_vi1); 157 | comm.add("VP2",do_vp2); 158 | comm.add("VI2",do_vi2); 159 | comm.add("TV",do_tv); 160 | comm.add("K31",do_K31); 161 | comm.add("K32",do_K32); 162 | comm.add("K33",do_K33); 163 | comm.add("K41",do_K41); 164 | comm.add("K42",do_K42); 165 | comm.add("K43",do_K43); 166 | v_p_1 = EEPROM.readFloat(12); 167 | v_i_1 = EEPROM.readFloat(16); 168 | v_p_2 = EEPROM.readFloat(20); 169 | v_i_2 = EEPROM.readFloat(24); 170 | motor.PID_velocity.P = v_p_1; 171 | motor.PID_velocity.I = v_i_1; 172 | #endif 173 | // kalman mpu6050 init 174 | Wire.begin(23, 5,400000UL);// Set I2C frequency to 400kHz 175 | i2cData[0] = 7; // Set the sample rate to 1000Hz - 8kHz/(7+1) = 1000Hz 176 | i2cData[1] = 0x00; // Disable FSYNC and set 260 Hz Acc filtering, 256 Hz Gyro filtering, 8 KHz sampling 177 | i2cData[2] = 0x00; // Set Gyro Full Scale Range to ±250deg/s 178 | i2cData[3] = 0x00; // Set Accelerometer Full Scale Range to ±2g 179 | while (i2cWrite(0x19, i2cData, 4, false)) 180 | ; // Write to all four registers at once 181 | while (i2cWrite(0x6B, 0x01, true)) 182 | ; // PLL with X axis gyroscope reference and disable sleep mode 183 | 184 | while (i2cRead(0x75, i2cData, 1)) 185 | ; 186 | if (i2cData[0] != 0x68) 187 | { // Read "WHO_AM_I" register 188 | Serial.print(F("Error reading sensor")); 189 | while (1) 190 | ; 191 | } 192 | 193 | delay(100); // Wait for sensor to stabilize 194 | 195 | /* Set kalman and gyro starting angle */ 196 | while (i2cRead(0x3B, i2cData, 6)) 197 | ; 198 | accX = (int16_t)((i2cData[0] << 8) | i2cData[1]); 199 | accY = (int16_t)((i2cData[2] << 8) | i2cData[3]); 200 | accZ = (int16_t)((i2cData[4] << 8) | i2cData[5]); 201 | double pitch = acc2rotation(accX, accY); 202 | 203 | kalmanZ.setAngle(pitch); 204 | gyroZangle = pitch; 205 | 206 | timer = micros(); 207 | Serial.println("kalman mpu6050 init"); 208 | 209 | //wifi初始化 210 | WiFi.mode(WIFI_AP); 211 | while(!WiFi.softAP(ssid, password)){}; //启动AP 212 | Serial.println("AP启动成功"); 213 | while (!udp.listen(localUdpPort)) //等待udp监听设置成功 214 | { 215 | } 216 | udp.onPacket(onPacketCallBack); //注册收到数据包事件 217 | 218 | I2Ctwo.begin(19, 18, 400000UL); //SDA,SCL 219 | sensor.init(&I2Ctwo); 220 | 221 | //连接motor对象与传感器对象 222 | motor.linkSensor(&sensor); 223 | 224 | //供电电压设置 [V] 225 | driver.voltage_power_supply = 12; 226 | driver.init(); 227 | 228 | //连接电机和driver对象 229 | motor.linkDriver(&driver); 230 | 231 | //FOC模型选择 232 | motor.foc_modulation = FOCModulationType::SpaceVectorPWM; 233 | 234 | //运动控制模式设置 235 | #if FLAG_V 236 | motor.controller = MotionControlType::torque; 237 | #else 238 | motor.controller = MotionControlType::velocity; 239 | //速度PI环设置 240 | motor.PID_velocity.P = 0.5; 241 | motor.PID_velocity.I = 20; 242 | #endif 243 | 244 | 245 | //最大电机限制电机 246 | motor.voltage_limit = 12; 247 | 248 | //速度低通滤波时间常数 249 | motor.LPF_velocity.Tf = 0.01; 250 | 251 | //设置最大速度限制 252 | motor.velocity_limit = 40; 253 | motor.voltage_sensor_align = 8; 254 | 255 | motor.useMonitoring(Serial); 256 | 257 | //初始化电机 258 | motor.init(); 259 | 260 | //初始化 FOC 261 | motor.initFOC(); 262 | 263 | Serial.println(F("Motor ready.")); 264 | Serial.println(F("Set the target velocity using serial terminal:")); 265 | 266 | 267 | } 268 | char buf[255]; 269 | long loop_count = 0; 270 | void loop() { 271 | motor.loopFOC(); 272 | if (1) 273 | { 274 | // loop_count++ == 10 275 | // loop_count = 0; 276 | while (i2cRead(0x3B, i2cData, 14)); 277 | accX = (int16_t)((i2cData[0] << 8) | i2cData[1]); 278 | accY = (int16_t)((i2cData[2] << 8) | i2cData[3]); 279 | accZ = (int16_t)((i2cData[4] << 8) | i2cData[5]); 280 | tempRaw = (int16_t)((i2cData[6] << 8) | i2cData[7]); 281 | gyroX = (int16_t)((i2cData[8] << 8) | i2cData[9]); 282 | gyroY = (int16_t)((i2cData[10] << 8) | i2cData[11]); 283 | gyroZ = (int16_t)((i2cData[12] << 8) | i2cData[13]); 284 | 285 | double dt = (double)(micros() - timer) / 1000000; // Calculate delta time 286 | timer = micros(); 287 | 288 | double pitch = acc2rotation(accX, accY); 289 | double gyroZrate = gyroZ / 131.0; // Convert to deg/s 290 | 291 | kalAngleZ = kalmanZ.getAngle(pitch, gyroZrate + gyroZ_OFF, dt); 292 | gyroZangle += (gyroZrate + gyroZ_OFF) * dt; 293 | compAngleZ = 0.93 * (compAngleZ + (gyroZrate + gyroZ_OFF) * dt) + 0.07 * pitch; 294 | 295 | // Reset the gyro angle when it has drifted too much 296 | if (gyroZangle < -180 || gyroZangle > 180) 297 | gyroZangle = kalAngleZ; 298 | 299 | float pendulum_angle = constrainAngle(fmod(kalAngleZ,120)-target_angle); 300 | // FLAG_V为1时使用电压控制,为0时候速度控制 301 | #if FLAG_V 302 | if (abs(pendulum_angle) < swing_up_angle) // if angle small enough stabilize 0.5~30°,1.5~90° 303 | { 304 | target_voltage = controllerLQR(pendulum_angle, gyroZrate, motor.shaftVelocity()); 305 | // limit the voltage set to the motor 306 | if (abs(target_voltage) > motor.voltage_limit * 0.7) 307 | target_voltage = _sign(target_voltage) * motor.voltage_limit * 0.7; 308 | } 309 | else // else do swing-up 310 | { // sets 1.5V to the motor in order to swing up 311 | target_voltage = -_sign(gyroZrate) * swing_up_voltage; 312 | } 313 | 314 | // set the target voltage to the motor 315 | if (accZ < -13000 && ((accX * accX + accY * accY) > (14000 * 14000))) 316 | { 317 | motor.move(0); 318 | } 319 | else 320 | { 321 | motor.move(lpf_throttle(target_voltage)); 322 | } 323 | 324 | #else 325 | if (abs(pendulum_angle) < swing_up_angle) // if angle small enough stabilize 0.5~30°,1.5~90° 326 | { 327 | target_velocity = controllerLQR(pendulum_angle, gyroZrate, motor.shaftVelocity()); 328 | if (abs(target_velocity) > 140) 329 | target_velocity = _sign(target_velocity) * 140; 330 | motor.controller = MotionControlType::velocity; 331 | motor.move(target_velocity); 332 | } 333 | else // else do swing-up 334 | { // sets 1.5V to the motor in order to swing up 335 | motor.controller = MotionControlType::torque; 336 | target_voltage = -_sign(gyroZrate) * swing_up_voltage; 337 | motor.move(target_voltage); 338 | } 339 | 340 | #endif 341 | #if 0 342 | 343 | //Serial.print(gyroZangle);Serial.print("\t"); 344 | Serial.print(kalAngleZ);Serial.print("\t"); 345 | 346 | Serial.print(target_voltage);Serial.print("\t"); 347 | // Serial.print(target_velocity);Serial.print("\t"); 348 | Serial.print(motor.shaft_velocity);Serial.print("\t"); 349 | Serial.print(target_angle);Serial.print("\t"); 350 | Serial.print(pendulum_angle);Serial.print("\t"); 351 | Serial.print(gyroZrate);Serial.print("\t"); 352 | Serial.print("\r\n"); 353 | #endif 354 | // motor.move(target_velocity); 355 | //可以使用该方法广播信息 356 | if(wifi_flag) 357 | { 358 | memset(buf, 0, strlen(buf)); 359 | 360 | wifi_print("v", motor.shaftVelocity()); 361 | wifi_print("vq",motor.voltage.q); 362 | wifi_print("p",pendulum_angle); 363 | wifi_print("t",target_angle); 364 | wifi_print("k",kalAngleZ); 365 | wifi_print("g",gyroZrate); 366 | 367 | udp.writeTo((const unsigned char*)buf, strlen(buf), IPAddress(192,168,4,2), localUdpPort); //广播数据 368 | } 369 | } 370 | } 371 | /* mpu6050加速度转换为角度 372 | acc2rotation(ax, ay) 373 | acc2rotation(az, ay) */ 374 | double acc2rotation(double x, double y) 375 | { 376 | if (y < 0) 377 | { 378 | return atan(x / y) / 1.570796 * 90 + 180; 379 | } 380 | else if (x < 0) 381 | { 382 | return (atan(x / y) / 1.570796 * 90 + 360); 383 | } 384 | else 385 | { 386 | return (atan(x / y) / 1.570796 * 90); 387 | } 388 | } 389 | 390 | // function constraining the angle in between -60~60 391 | float constrainAngle(float x) 392 | { 393 | float a = 0; 394 | if(x < 0) 395 | { 396 | a = 120+x; 397 | if(a 2.5) 414 | { 415 | last_unstable_time = millis(); 416 | if(stable) 417 | { 418 | target_angle = EEPROM.readFloat(0); 419 | stable = 0; 420 | } 421 | } 422 | if ((millis() - last_unstable_time) > 1000&&!stable) 423 | { 424 | target_angle = target_angle+p_angle; 425 | stable = 1; 426 | } 427 | 428 | //Serial.println(stable); 429 | float u; 430 | #if FLAG_V 431 | if (!stable) 432 | { 433 | u = LQR_K1_1 * p_angle + LQR_K1_2 * p_vel + LQR_K1_3 * m_vel; 434 | } 435 | else 436 | { 437 | //u = LQR_K1 * p_angle + LQR_K2 * p_vel + LQR_K3 * m_vel; 438 | u = LQR_K2_1 * p_angle + LQR_K2_2 * p_vel + LQR_K2_3 * m_vel; 439 | } 440 | #else 441 | if (!stable) 442 | { 443 | motor.PID_velocity.P = v_p_1; 444 | motor.PID_velocity.I = v_i_1; 445 | u = LQR_K3_1 * p_angle + LQR_K3_2 * p_vel + LQR_K3_3 * m_vel; 446 | } 447 | else 448 | { 449 | motor.PID_velocity.P = v_p_2; 450 | motor.PID_velocity.I = v_i_2; 451 | //u = LQR_K1 * p_angle + LQR_K2 * p_vel + LQR_K3 * m_vel; 452 | u = LQR_K4_1 * p_angle + LQR_K4_2 * p_vel + LQR_K4_3 * m_vel; 453 | } 454 | #endif 455 | return u; 456 | } 457 | void wifi_print(char * s,double num) 458 | { 459 | char str[255]; 460 | char n[255]; 461 | sprintf(n, "%.2f",num); 462 | strcpy(str,s); 463 | strcat(str, n); 464 | strcat(buf+strlen(buf), str); 465 | strcat(buf, ",\0"); 466 | 467 | } 468 | -------------------------------------------------------------------------------- /DengFOC 莱洛三角形程序/lailuo/rewrite.cpp: -------------------------------------------------------------------------------- 1 | #include 2 | #include "Command.h" 3 | #include 4 | #include //引用以使用异步UDP 5 | #include "Kalman.h" // Source: https://github.com/TKJElectronics/KalmanFilter 6 | #include "EEPROM.h" 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | GNU AFFERO GENERAL PUBLIC LICENSE 2 | Version 3, 19 November 2007 3 | 4 | Copyright (C) 2007 Free Software Foundation, Inc. 5 | Everyone is permitted to copy and distribute verbatim copies 6 | of this license document, but changing it is not allowed. 7 | 8 | Preamble 9 | 10 | The GNU Affero General Public License is a free, copyleft license for 11 | software and other kinds of works, specifically designed to ensure 12 | cooperation with the community in the case of network server software. 13 | 14 | The licenses for most software and other practical works are designed 15 | to take away your freedom to share and change the works. By contrast, 16 | our General Public Licenses are intended to guarantee your freedom to 17 | share and change all versions of a program--to make sure it remains free 18 | software for all its users. 19 | 20 | When we speak of free software, we are referring to freedom, not 21 | price. Our General Public Licenses are designed to make sure that you 22 | have the freedom to distribute copies of free software (and charge for 23 | them if you wish), that you receive source code or can get it if you 24 | want it, that you can change the software or use pieces of it in new 25 | free programs, and that you know you can do these things. 26 | 27 | Developers that use our General Public Licenses protect your rights 28 | with two steps: (1) assert copyright on the software, and (2) offer 29 | you this License which gives you legal permission to copy, distribute 30 | and/or modify the software. 31 | 32 | A secondary benefit of defending all users' freedom is that 33 | improvements made in alternate versions of the program, if they 34 | receive widespread use, become available for other developers to 35 | incorporate. Many developers of free software are heartened and 36 | encouraged by the resulting cooperation. However, in the case of 37 | software used on network servers, this result may fail to come about. 38 | The GNU General Public License permits making a modified version and 39 | letting the public access it on a server without ever releasing its 40 | source code to the public. 41 | 42 | The GNU Affero General Public License is designed specifically to 43 | ensure that, in such cases, the modified source code becomes available 44 | to the community. It requires the operator of a network server to 45 | provide the source code of the modified version running there to the 46 | users of that server. Therefore, public use of a modified version, on 47 | a publicly accessible server, gives the public access to the source 48 | code of the modified version. 49 | 50 | An older license, called the Affero General Public License and 51 | published by Affero, was designed to accomplish similar goals. This is 52 | a different license, not a version of the Affero GPL, but Affero has 53 | released a new version of the Affero GPL which permits relicensing under 54 | this license. 55 | 56 | The precise terms and conditions for copying, distribution and 57 | modification follow. 58 | 59 | TERMS AND CONDITIONS 60 | 61 | 0. Definitions. 62 | 63 | "This License" refers to version 3 of the GNU Affero General Public License. 64 | 65 | "Copyright" also means copyright-like laws that apply to other kinds of 66 | works, such as semiconductor masks. 67 | 68 | "The Program" refers to any copyrightable work licensed under this 69 | License. Each licensee is addressed as "you". "Licensees" and 70 | "recipients" may be individuals or organizations. 71 | 72 | To "modify" a work means to copy from or adapt all or part of the work 73 | in a fashion requiring copyright permission, other than the making of an 74 | exact copy. The resulting work is called a "modified version" of the 75 | earlier work or a work "based on" the earlier work. 76 | 77 | A "covered work" means either the unmodified Program or a work based 78 | on the Program. 79 | 80 | To "propagate" a work means to do anything with it that, without 81 | permission, would make you directly or secondarily liable for 82 | infringement under applicable copyright law, except executing it on a 83 | computer or modifying a private copy. Propagation includes copying, 84 | distribution (with or without modification), making available to the 85 | public, and in some countries other activities as well. 86 | 87 | To "convey" a work means any kind of propagation that enables other 88 | parties to make or receive copies. Mere interaction with a user through 89 | a computer network, with no transfer of a copy, is not conveying. 90 | 91 | An interactive user interface displays "Appropriate Legal Notices" 92 | to the extent that it includes a convenient and prominently visible 93 | feature that (1) displays an appropriate copyright notice, and (2) 94 | tells the user that there is no warranty for the work (except to the 95 | extent that warranties are provided), that licensees may convey the 96 | work under this License, and how to view a copy of this License. If 97 | the interface presents a list of user commands or options, such as a 98 | menu, a prominent item in the list meets this criterion. 99 | 100 | 1. Source Code. 101 | 102 | The "source code" for a work means the preferred form of the work 103 | for making modifications to it. "Object code" means any non-source 104 | form of a work. 105 | 106 | A "Standard Interface" means an interface that either is an official 107 | standard defined by a recognized standards body, or, in the case of 108 | interfaces specified for a particular programming language, one that 109 | is widely used among developers working in that language. 110 | 111 | The "System Libraries" of an executable work include anything, other 112 | than the work as a whole, that (a) is included in the normal form of 113 | packaging a Major Component, but which is not part of that Major 114 | Component, and (b) serves only to enable use of the work with that 115 | Major Component, or to implement a Standard Interface for which an 116 | implementation is available to the public in source code form. A 117 | "Major Component", in this context, means a major essential component 118 | (kernel, window system, and so on) of the specific operating system 119 | (if any) on which the executable work runs, or a compiler used to 120 | produce the work, or an object code interpreter used to run it. 121 | 122 | The "Corresponding Source" for a work in object code form means all 123 | the source code needed to generate, install, and (for an executable 124 | work) run the object code and to modify the work, including scripts to 125 | control those activities. However, it does not include the work's 126 | System Libraries, or general-purpose tools or generally available free 127 | programs which are used unmodified in performing those activities but 128 | which are not part of the work. For example, Corresponding Source 129 | includes interface definition files associated with source files for 130 | the work, and the source code for shared libraries and dynamically 131 | linked subprograms that the work is specifically designed to require, 132 | such as by intimate data communication or control flow between those 133 | subprograms and other parts of the work. 134 | 135 | The Corresponding Source need not include anything that users 136 | can regenerate automatically from other parts of the Corresponding 137 | Source. 138 | 139 | The Corresponding Source for a work in source code form is that 140 | same work. 141 | 142 | 2. Basic Permissions. 143 | 144 | All rights granted under this License are granted for the term of 145 | copyright on the Program, and are irrevocable provided the stated 146 | conditions are met. This License explicitly affirms your unlimited 147 | permission to run the unmodified Program. The output from running a 148 | covered work is covered by this License only if the output, given its 149 | content, constitutes a covered work. This License acknowledges your 150 | rights of fair use or other equivalent, as provided by copyright law. 151 | 152 | You may make, run and propagate covered works that you do not 153 | convey, without conditions so long as your license otherwise remains 154 | in force. You may convey covered works to others for the sole purpose 155 | of having them make modifications exclusively for you, or provide you 156 | with facilities for running those works, provided that you comply with 157 | the terms of this License in conveying all material for which you do 158 | not control copyright. Those thus making or running the covered works 159 | for you must do so exclusively on your behalf, under your direction 160 | and control, on terms that prohibit them from making any copies of 161 | your copyrighted material outside their relationship with you. 162 | 163 | Conveying under any other circumstances is permitted solely under 164 | the conditions stated below. Sublicensing is not allowed; section 10 165 | makes it unnecessary. 166 | 167 | 3. Protecting Users' Legal Rights From Anti-Circumvention Law. 168 | 169 | No covered work shall be deemed part of an effective technological 170 | measure under any applicable law fulfilling obligations under article 171 | 11 of the WIPO copyright treaty adopted on 20 December 1996, or 172 | similar laws prohibiting or restricting circumvention of such 173 | measures. 174 | 175 | When you convey a covered work, you waive any legal power to forbid 176 | circumvention of technological measures to the extent such circumvention 177 | is effected by exercising rights under this License with respect to 178 | the covered work, and you disclaim any intention to limit operation or 179 | modification of the work as a means of enforcing, against the work's 180 | users, your or third parties' legal rights to forbid circumvention of 181 | technological measures. 182 | 183 | 4. Conveying Verbatim Copies. 184 | 185 | You may convey verbatim copies of the Program's source code as you 186 | receive it, in any medium, provided that you conspicuously and 187 | appropriately publish on each copy an appropriate copyright notice; 188 | keep intact all notices stating that this License and any 189 | non-permissive terms added in accord with section 7 apply to the code; 190 | keep intact all notices of the absence of any warranty; and give all 191 | recipients a copy of this License along with the Program. 192 | 193 | You may charge any price or no price for each copy that you convey, 194 | and you may offer support or warranty protection for a fee. 195 | 196 | 5. Conveying Modified Source Versions. 197 | 198 | You may convey a work based on the Program, or the modifications to 199 | produce it from the Program, in the form of source code under the 200 | terms of section 4, provided that you also meet all of these conditions: 201 | 202 | a) The work must carry prominent notices stating that you modified 203 | it, and giving a relevant date. 204 | 205 | b) The work must carry prominent notices stating that it is 206 | released under this License and any conditions added under section 207 | 7. This requirement modifies the requirement in section 4 to 208 | "keep intact all notices". 209 | 210 | c) You must license the entire work, as a whole, under this 211 | License to anyone who comes into possession of a copy. This 212 | License will therefore apply, along with any applicable section 7 213 | additional terms, to the whole of the work, and all its parts, 214 | regardless of how they are packaged. This License gives no 215 | permission to license the work in any other way, but it does not 216 | invalidate such permission if you have separately received it. 217 | 218 | d) If the work has interactive user interfaces, each must display 219 | Appropriate Legal Notices; however, if the Program has interactive 220 | interfaces that do not display Appropriate Legal Notices, your 221 | work need not make them do so. 222 | 223 | A compilation of a covered work with other separate and independent 224 | works, which are not by their nature extensions of the covered work, 225 | and which are not combined with it such as to form a larger program, 226 | in or on a volume of a storage or distribution medium, is called an 227 | "aggregate" if the compilation and its resulting copyright are not 228 | used to limit the access or legal rights of the compilation's users 229 | beyond what the individual works permit. Inclusion of a covered work 230 | in an aggregate does not cause this License to apply to the other 231 | parts of the aggregate. 232 | 233 | 6. Conveying Non-Source Forms. 234 | 235 | You may convey a covered work in object code form under the terms 236 | of sections 4 and 5, provided that you also convey the 237 | machine-readable Corresponding Source under the terms of this License, 238 | in one of these ways: 239 | 240 | a) Convey the object code in, or embodied in, a physical product 241 | (including a physical distribution medium), accompanied by the 242 | Corresponding Source fixed on a durable physical medium 243 | customarily used for software interchange. 244 | 245 | b) Convey the object code in, or embodied in, a physical product 246 | (including a physical distribution medium), accompanied by a 247 | written offer, valid for at least three years and valid for as 248 | long as you offer spare parts or customer support for that product 249 | model, to give anyone who possesses the object code either (1) a 250 | copy of the Corresponding Source for all the software in the 251 | product that is covered by this License, on a durable physical 252 | medium customarily used for software interchange, for a price no 253 | more than your reasonable cost of physically performing this 254 | conveying of source, or (2) access to copy the 255 | Corresponding Source from a network server at no charge. 256 | 257 | c) Convey individual copies of the object code with a copy of the 258 | written offer to provide the Corresponding Source. This 259 | alternative is allowed only occasionally and noncommercially, and 260 | only if you received the object code with such an offer, in accord 261 | with subsection 6b. 262 | 263 | d) Convey the object code by offering access from a designated 264 | place (gratis or for a charge), and offer equivalent access to the 265 | Corresponding Source in the same way through the same place at no 266 | further charge. You need not require recipients to copy the 267 | Corresponding Source along with the object code. If the place to 268 | copy the object code is a network server, the Corresponding Source 269 | may be on a different server (operated by you or a third party) 270 | that supports equivalent copying facilities, provided you maintain 271 | clear directions next to the object code saying where to find the 272 | Corresponding Source. Regardless of what server hosts the 273 | Corresponding Source, you remain obligated to ensure that it is 274 | available for as long as needed to satisfy these requirements. 275 | 276 | e) Convey the object code using peer-to-peer transmission, provided 277 | you inform other peers where the object code and Corresponding 278 | Source of the work are being offered to the general public at no 279 | charge under subsection 6d. 280 | 281 | A separable portion of the object code, whose source code is excluded 282 | from the Corresponding Source as a System Library, need not be 283 | included in conveying the object code work. 284 | 285 | A "User Product" is either (1) a "consumer product", which means any 286 | tangible personal property which is normally used for personal, family, 287 | or household purposes, or (2) anything designed or sold for incorporation 288 | into a dwelling. In determining whether a product is a consumer product, 289 | doubtful cases shall be resolved in favor of coverage. For a particular 290 | product received by a particular user, "normally used" refers to a 291 | typical or common use of that class of product, regardless of the status 292 | of the particular user or of the way in which the particular user 293 | actually uses, or expects or is expected to use, the product. A product 294 | is a consumer product regardless of whether the product has substantial 295 | commercial, industrial or non-consumer uses, unless such uses represent 296 | the only significant mode of use of the product. 297 | 298 | "Installation Information" for a User Product means any methods, 299 | procedures, authorization keys, or other information required to install 300 | and execute modified versions of a covered work in that User Product from 301 | a modified version of its Corresponding Source. The information must 302 | suffice to ensure that the continued functioning of the modified object 303 | code is in no case prevented or interfered with solely because 304 | modification has been made. 305 | 306 | If you convey an object code work under this section in, or with, or 307 | specifically for use in, a User Product, and the conveying occurs as 308 | part of a transaction in which the right of possession and use of the 309 | User Product is transferred to the recipient in perpetuity or for a 310 | fixed term (regardless of how the transaction is characterized), the 311 | Corresponding Source conveyed under this section must be accompanied 312 | by the Installation Information. But this requirement does not apply 313 | if neither you nor any third party retains the ability to install 314 | modified object code on the User Product (for example, the work has 315 | been installed in ROM). 316 | 317 | The requirement to provide Installation Information does not include a 318 | requirement to continue to provide support service, warranty, or updates 319 | for a work that has been modified or installed by the recipient, or for 320 | the User Product in which it has been modified or installed. Access to a 321 | network may be denied when the modification itself materially and 322 | adversely affects the operation of the network or violates the rules and 323 | protocols for communication across the network. 324 | 325 | Corresponding Source conveyed, and Installation Information provided, 326 | in accord with this section must be in a format that is publicly 327 | documented (and with an implementation available to the public in 328 | source code form), and must require no special password or key for 329 | unpacking, reading or copying. 330 | 331 | 7. Additional Terms. 332 | 333 | "Additional permissions" are terms that supplement the terms of this 334 | License by making exceptions from one or more of its conditions. 335 | Additional permissions that are applicable to the entire Program shall 336 | be treated as though they were included in this License, to the extent 337 | that they are valid under applicable law. If additional permissions 338 | apply only to part of the Program, that part may be used separately 339 | under those permissions, but the entire Program remains governed by 340 | this License without regard to the additional permissions. 341 | 342 | When you convey a copy of a covered work, you may at your option 343 | remove any additional permissions from that copy, or from any part of 344 | it. (Additional permissions may be written to require their own 345 | removal in certain cases when you modify the work.) You may place 346 | additional permissions on material, added by you to a covered work, 347 | for which you have or can give appropriate copyright permission. 348 | 349 | Notwithstanding any other provision of this License, for material you 350 | add to a covered work, you may (if authorized by the copyright holders of 351 | that material) supplement the terms of this License with terms: 352 | 353 | a) Disclaiming warranty or limiting liability differently from the 354 | terms of sections 15 and 16 of this License; or 355 | 356 | b) Requiring preservation of specified reasonable legal notices or 357 | author attributions in that material or in the Appropriate Legal 358 | Notices displayed by works containing it; or 359 | 360 | c) Prohibiting misrepresentation of the origin of that material, or 361 | requiring that modified versions of such material be marked in 362 | reasonable ways as different from the original version; or 363 | 364 | d) Limiting the use for publicity purposes of names of licensors or 365 | authors of the material; or 366 | 367 | e) Declining to grant rights under trademark law for use of some 368 | trade names, trademarks, or service marks; or 369 | 370 | f) Requiring indemnification of licensors and authors of that 371 | material by anyone who conveys the material (or modified versions of 372 | it) with contractual assumptions of liability to the recipient, for 373 | any liability that these contractual assumptions directly impose on 374 | those licensors and authors. 375 | 376 | All other non-permissive additional terms are considered "further 377 | restrictions" within the meaning of section 10. If the Program as you 378 | received it, or any part of it, contains a notice stating that it is 379 | governed by this License along with a term that is a further 380 | restriction, you may remove that term. If a license document contains 381 | a further restriction but permits relicensing or conveying under this 382 | License, you may add to a covered work material governed by the terms 383 | of that license document, provided that the further restriction does 384 | not survive such relicensing or conveying. 385 | 386 | If you add terms to a covered work in accord with this section, you 387 | must place, in the relevant source files, a statement of the 388 | additional terms that apply to those files, or a notice indicating 389 | where to find the applicable terms. 390 | 391 | Additional terms, permissive or non-permissive, may be stated in the 392 | form of a separately written license, or stated as exceptions; 393 | the above requirements apply either way. 394 | 395 | 8. Termination. 396 | 397 | You may not propagate or modify a covered work except as expressly 398 | provided under this License. Any attempt otherwise to propagate or 399 | modify it is void, and will automatically terminate your rights under 400 | this License (including any patent licenses granted under the third 401 | paragraph of section 11). 402 | 403 | However, if you cease all violation of this License, then your 404 | license from a particular copyright holder is reinstated (a) 405 | provisionally, unless and until the copyright holder explicitly and 406 | finally terminates your license, and (b) permanently, if the copyright 407 | holder fails to notify you of the violation by some reasonable means 408 | prior to 60 days after the cessation. 409 | 410 | Moreover, your license from a particular copyright holder is 411 | reinstated permanently if the copyright holder notifies you of the 412 | violation by some reasonable means, this is the first time you have 413 | received notice of violation of this License (for any work) from that 414 | copyright holder, and you cure the violation prior to 30 days after 415 | your receipt of the notice. 416 | 417 | Termination of your rights under this section does not terminate the 418 | licenses of parties who have received copies or rights from you under 419 | this License. If your rights have been terminated and not permanently 420 | reinstated, you do not qualify to receive new licenses for the same 421 | material under section 10. 422 | 423 | 9. Acceptance Not Required for Having Copies. 424 | 425 | You are not required to accept this License in order to receive or 426 | run a copy of the Program. Ancillary propagation of a covered work 427 | occurring solely as a consequence of using peer-to-peer transmission 428 | to receive a copy likewise does not require acceptance. However, 429 | nothing other than this License grants you permission to propagate or 430 | modify any covered work. These actions infringe copyright if you do 431 | not accept this License. Therefore, by modifying or propagating a 432 | covered work, you indicate your acceptance of this License to do so. 433 | 434 | 10. Automatic Licensing of Downstream Recipients. 435 | 436 | Each time you convey a covered work, the recipient automatically 437 | receives a license from the original licensors, to run, modify and 438 | propagate that work, subject to this License. You are not responsible 439 | for enforcing compliance by third parties with this License. 440 | 441 | An "entity transaction" is a transaction transferring control of an 442 | organization, or substantially all assets of one, or subdividing an 443 | organization, or merging organizations. If propagation of a covered 444 | work results from an entity transaction, each party to that 445 | transaction who receives a copy of the work also receives whatever 446 | licenses to the work the party's predecessor in interest had or could 447 | give under the previous paragraph, plus a right to possession of the 448 | Corresponding Source of the work from the predecessor in interest, if 449 | the predecessor has it or can get it with reasonable efforts. 450 | 451 | You may not impose any further restrictions on the exercise of the 452 | rights granted or affirmed under this License. For example, you may 453 | not impose a license fee, royalty, or other charge for exercise of 454 | rights granted under this License, and you may not initiate litigation 455 | (including a cross-claim or counterclaim in a lawsuit) alleging that 456 | any patent claim is infringed by making, using, selling, offering for 457 | sale, or importing the Program or any portion of it. 458 | 459 | 11. Patents. 460 | 461 | A "contributor" is a copyright holder who authorizes use under this 462 | License of the Program or a work on which the Program is based. The 463 | work thus licensed is called the contributor's "contributor version". 464 | 465 | A contributor's "essential patent claims" are all patent claims 466 | owned or controlled by the contributor, whether already acquired or 467 | hereafter acquired, that would be infringed by some manner, permitted 468 | by this License, of making, using, or selling its contributor version, 469 | but do not include claims that would be infringed only as a 470 | consequence of further modification of the contributor version. For 471 | purposes of this definition, "control" includes the right to grant 472 | patent sublicenses in a manner consistent with the requirements of 473 | this License. 474 | 475 | Each contributor grants you a non-exclusive, worldwide, royalty-free 476 | patent license under the contributor's essential patent claims, to 477 | make, use, sell, offer for sale, import and otherwise run, modify and 478 | propagate the contents of its contributor version. 479 | 480 | In the following three paragraphs, a "patent license" is any express 481 | agreement or commitment, however denominated, not to enforce a patent 482 | (such as an express permission to practice a patent or covenant not to 483 | sue for patent infringement). To "grant" such a patent license to a 484 | party means to make such an agreement or commitment not to enforce a 485 | patent against the party. 486 | 487 | If you convey a covered work, knowingly relying on a patent license, 488 | and the Corresponding Source of the work is not available for anyone 489 | to copy, free of charge and under the terms of this License, through a 490 | publicly available network server or other readily accessible means, 491 | then you must either (1) cause the Corresponding Source to be so 492 | available, or (2) arrange to deprive yourself of the benefit of the 493 | patent license for this particular work, or (3) arrange, in a manner 494 | consistent with the requirements of this License, to extend the patent 495 | license to downstream recipients. "Knowingly relying" means you have 496 | actual knowledge that, but for the patent license, your conveying the 497 | covered work in a country, or your recipient's use of the covered work 498 | in a country, would infringe one or more identifiable patents in that 499 | country that you have reason to believe are valid. 500 | 501 | If, pursuant to or in connection with a single transaction or 502 | arrangement, you convey, or propagate by procuring conveyance of, a 503 | covered work, and grant a patent license to some of the parties 504 | receiving the covered work authorizing them to use, propagate, modify 505 | or convey a specific copy of the covered work, then the patent license 506 | you grant is automatically extended to all recipients of the covered 507 | work and works based on it. 508 | 509 | A patent license is "discriminatory" if it does not include within 510 | the scope of its coverage, prohibits the exercise of, or is 511 | conditioned on the non-exercise of one or more of the rights that are 512 | specifically granted under this License. You may not convey a covered 513 | work if you are a party to an arrangement with a third party that is 514 | in the business of distributing software, under which you make payment 515 | to the third party based on the extent of your activity of conveying 516 | the work, and under which the third party grants, to any of the 517 | parties who would receive the covered work from you, a discriminatory 518 | patent license (a) in connection with copies of the covered work 519 | conveyed by you (or copies made from those copies), or (b) primarily 520 | for and in connection with specific products or compilations that 521 | contain the covered work, unless you entered into that arrangement, 522 | or that patent license was granted, prior to 28 March 2007. 523 | 524 | Nothing in this License shall be construed as excluding or limiting 525 | any implied license or other defenses to infringement that may 526 | otherwise be available to you under applicable patent law. 527 | 528 | 12. No Surrender of Others' Freedom. 529 | 530 | If conditions are imposed on you (whether by court order, agreement or 531 | otherwise) that contradict the conditions of this License, they do not 532 | excuse you from the conditions of this License. If you cannot convey a 533 | covered work so as to satisfy simultaneously your obligations under this 534 | License and any other pertinent obligations, then as a consequence you may 535 | not convey it at all. For example, if you agree to terms that obligate you 536 | to collect a royalty for further conveying from those to whom you convey 537 | the Program, the only way you could satisfy both those terms and this 538 | License would be to refrain entirely from conveying the Program. 539 | 540 | 13. Remote Network Interaction; Use with the GNU General Public License. 541 | 542 | Notwithstanding any other provision of this License, if you modify the 543 | Program, your modified version must prominently offer all users 544 | interacting with it remotely through a computer network (if your version 545 | supports such interaction) an opportunity to receive the Corresponding 546 | Source of your version by providing access to the Corresponding Source 547 | from a network server at no charge, through some standard or customary 548 | means of facilitating copying of software. This Corresponding Source 549 | shall include the Corresponding Source for any work covered by version 3 550 | of the GNU General Public License that is incorporated pursuant to the 551 | following paragraph. 552 | 553 | Notwithstanding any other provision of this License, you have 554 | permission to link or combine any covered work with a work licensed 555 | under version 3 of the GNU General Public License into a single 556 | combined work, and to convey the resulting work. The terms of this 557 | License will continue to apply to the part which is the covered work, 558 | but the work with which it is combined will remain governed by version 559 | 3 of the GNU General Public License. 560 | 561 | 14. Revised Versions of this License. 562 | 563 | The Free Software Foundation may publish revised and/or new versions of 564 | the GNU Affero General Public License from time to time. Such new versions 565 | will be similar in spirit to the present version, but may differ in detail to 566 | address new problems or concerns. 567 | 568 | Each version is given a distinguishing version number. If the 569 | Program specifies that a certain numbered version of the GNU Affero General 570 | Public License "or any later version" applies to it, you have the 571 | option of following the terms and conditions either of that numbered 572 | version or of any later version published by the Free Software 573 | Foundation. If the Program does not specify a version number of the 574 | GNU Affero General Public License, you may choose any version ever published 575 | by the Free Software Foundation. 576 | 577 | If the Program specifies that a proxy can decide which future 578 | versions of the GNU Affero General Public License can be used, that proxy's 579 | public statement of acceptance of a version permanently authorizes you 580 | to choose that version for the Program. 581 | 582 | Later license versions may give you additional or different 583 | permissions. However, no additional obligations are imposed on any 584 | author or copyright holder as a result of your choosing to follow a 585 | later version. 586 | 587 | 15. Disclaimer of Warranty. 588 | 589 | THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY 590 | APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT 591 | HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY 592 | OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, 593 | THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 594 | PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM 595 | IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF 596 | ALL NECESSARY SERVICING, REPAIR OR CORRECTION. 597 | 598 | 16. Limitation of Liability. 599 | 600 | IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING 601 | WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS 602 | THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY 603 | GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE 604 | USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF 605 | DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD 606 | PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), 607 | EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF 608 | SUCH DAMAGES. 609 | 610 | 17. Interpretation of Sections 15 and 16. 611 | 612 | If the disclaimer of warranty and limitation of liability provided 613 | above cannot be given local legal effect according to their terms, 614 | reviewing courts shall apply local law that most closely approximates 615 | an absolute waiver of all civil liability in connection with the 616 | Program, unless a warranty or assumption of liability accompanies a 617 | copy of the Program in return for a fee. 618 | 619 | END OF TERMS AND CONDITIONS 620 | 621 | How to Apply These Terms to Your New Programs 622 | 623 | If you develop a new program, and you want it to be of the greatest 624 | possible use to the public, the best way to achieve this is to make it 625 | free software which everyone can redistribute and change under these terms. 626 | 627 | To do so, attach the following notices to the program. It is safest 628 | to attach them to the start of each source file to most effectively 629 | state the exclusion of warranty; and each file should have at least 630 | the "copyright" line and a pointer to where the full notice is found. 631 | 632 | 633 | Copyright (C) 634 | 635 | This program is free software: you can redistribute it and/or modify 636 | it under the terms of the GNU Affero General Public License as published 637 | by the Free Software Foundation, either version 3 of the License, or 638 | (at your option) any later version. 639 | 640 | This program is distributed in the hope that it will be useful, 641 | but WITHOUT ANY WARRANTY; without even the implied warranty of 642 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 643 | GNU Affero General Public License for more details. 644 | 645 | You should have received a copy of the GNU Affero General Public License 646 | along with this program. If not, see . 647 | 648 | Also add information on how to contact you by electronic and paper mail. 649 | 650 | If your software can interact with users remotely through a computer 651 | network, you should also make sure that it provides a way for users to 652 | get its source. For example, if your program is a web application, its 653 | interface could display a "Source" link that leads users to an archive 654 | of the code. There are many ways you could offer source, and different 655 | solutions will be better for different programs; see section 13 for the 656 | specific requirements. 657 | 658 | You should also get your employer (if you work as a programmer) or school, 659 | if any, to sign a "copyright disclaimer" for the program, if necessary. 660 | For more information on this, and how to apply and follow the GNU AGPL, see 661 | . 662 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # DengFOC莱洛LQR自平衡三角形项目 2 | **DengFOC莱洛LQR自平衡三角形**是基于45同学开源的[莱洛三角形项目](https://gitee.com/coll45/foc),进行结构改进和效果优化后应用在我开源的[DengFOC](https://github.com/ToanTech/Deng-s-foc-controller)双路无刷电机驱动器上的DengFOC配套项目。 3 | 4 | **项目完全开源,你可以根据本Github内容自行白嫖,或者,支持一下灯哥的辛勤劳作,进入灯哥开源TB店购买DengFOC莱洛自平衡三角形套件,一键配齐。** 5 | 6 | [DengFOC动莱洛自平衡三角形套件--链接猛击(进店后在 所有宝贝 处可找到)](https://shop564514875.taobao.com/) 7 | 8 | ![image1](pic/effect.gif) 9 | 10 | ![image1](pic/effect2.gif) 11 | 12 | ## 1 视频教程 13 | 14 | 配套本开源项目,灯哥精心制作了全组装过程视频教程和算法原理课,请点击查看: 15 | 16 | [1 DengFOC LQR莱洛三角形--效果展示](https://www.bilibili.com/video/BV1Mg411o7hd/) 17 | 18 | [2 DengFOC LQR莱洛三角形算法原理和DIY实现](https://www.bilibili.com/video/BV1QG4y1Y76f/) 19 | 20 | ## 2 接线 21 | 22 | 只要你手头有一块DengFOC V3(你可以在TB搜索**灯哥开源**进入店铺购买,或根据[DengFOC开源仓库](https://github.com/ToanTech/Deng-s-foc-controller)的开源资料自制)就可以快速搭接出此项目,项目供电默认电压为12V(3S航模电池),除DengFOC外,其它电子元器件主要由一个2204无刷电机,两个 AS5600 编码器,一个 MPU6050 组成。其接线表格如下,其中,接线位置指的是DengFOC无刷驱动板上的针脚位置: 23 | 24 | | 零件 | 接线位置 | 25 | | -------- | --------------------------- | 26 | | 2204电机 | DengFOC M0位置(无刷电机0) | 27 | | AS5600 | SDA0,SCL0,3V3,GND | 28 | | MPU6050 | SDA1,SCL1,3V3,GND | 29 | 30 |
31 | 32 | 如果你是自行DIY,那么按照上面的接线表格将线接入DengFOC即可;如果你是采用在 [灯哥开源 淘宝店](https://shop564514875.taobao.com/) 购买的莱洛三角形套件,那么你会得到**如下图所示配套线材**。 33 | 34 | 配套的接线材料有:两套接线,一套是AS5600的线,一头是杜邦端子,接有两根黑线GND,一根红线VCC,一根绿线SDA,一根黄线SCL;另一端是两个3p端子,其中一个3p端子接绿色SDA,黄色SCL,黑色DIR;另一个是接红色VCC,黑色GND,如下图中左边的线所示。 35 | 36 | 另一套是MPU6050的线,一头是杜邦端子,接有一根黑线GND,一根红线VCC,一根黄线SCL,一根绿线SDA;另一端接一个4p端子),如下图中右边的线: 37 | 38 | ![image1](pic/xc.jpg) 39 | 40 | ### 2.1 对于 AS5600 41 | 42 | 首先,将上图左边的线按照下图所示穿过三角块和底板打印件: 43 | 44 | ![image1](pic/jxbz3.jpg) 45 | 46 | 接着,将线的其中一个3p端子接GND、SCL和SDA线,其中GND为黑色线,SCL为黄色线,SDA为绿色线;另一个只连着两条线的端子用来接VCC和GND,VCC为红色线,GND为黑色线。接线位置如下图所示: 47 | 48 | ![image1](pic/jxbz1.jpg) 49 | 50 | ![image1](pic/jxbz2.jpg) 51 | 52 | 最后,将杜邦线的另一端按照下图的顺序接在DengFOC的杜邦端口上: 53 | 54 | ![image1](pic/jxbz4.jpg) 55 | 56 | 这就是AS5600的接线过程。 57 | 58 | ### 2.2 对于MPU6050 59 | 60 | 首先,将MPU6050的四根线穿过三角块和底板打印件,如下图所示: 61 | 62 | ![image1](pic/jxbz6.jpg) 63 | 64 | 将4P端子按下图的顺序接SDA,SCL,GND,VCC线,SDA为绿色线, SCL为黄色线,GND为黑色线,VCC为红色线 65 | 66 | ![image1](pic/jxbz5.jpg) 67 | 68 | 再将杜邦线的另一端按照下图的顺序接在杜邦端口: 69 | 70 | ![image1](pic/jxbz7.jpg) 71 | 72 | 这就是MPU6050的接线步骤 73 | 74 | ### 2.3 对于电机 75 | 76 | 直接接到电机M0接口(无刷电机0)接口即可,若接入后,在调试过程中发现动量轮不能减小误差,反而会加剧误差的话,证明电机转向接反,此时对调电机其中两根相线即可。 77 | 78 | ## 3 零件制造 79 | 80 | 莱洛三角形的由两种DIY方式,一个是**3D打印版本**;一个是**激光切割的木材板版本** 81 | 82 | **对于3D打印版本**:主要零件为3D打印,下载文件夹中的图纸,全100%密度打印即可。 83 | 84 | **对于激光切割的木材版版本**:底板为激光切割,固定三角型为3D打印,下载文件夹中的图纸,对应进行切割和打印即可。 85 | 86 | 零件打印图纸和木材板切割图纸都可以在本项目的开源文件夹中找到。 87 | 88 | ## 4 下载程序 89 | 90 | 下载项目文件夹中的 lailuo.ino 程序,用Arduino IDE打开,用串口连接DengFOC,即可按照与一般Arduino一致的方法上传。 91 | 92 | ## 5 调试 93 | 94 | 在安装好机械结构后,本莱洛三角形的调试可以采用45同学开发的调试工具进行调试,调试步骤如下: 95 | 96 | 打开 **调试上位机** 中自带的可执行文件_main文件夹,点击main.exe文件进入交互界面: 97 | 98 | ![ts1](pic/ts1.png) 99 | 100 | ![ts1](pic/ts2.png) 101 | 102 | 进入之后的界面如下: 103 | 104 | ![ts1](pic/ts3.png) 105 | 106 | 要使用这个调试软件,首先要先将莱洛三角形上电,然后在WiFi列表中找到**esp32_lailuo**这个WiFi,并连接(WiFi密码可以在源程序中找到)。 107 | 108 | ![ts1](pic/ts5.png) 109 | 110 | 已经连接WiFi之后点击设置键,就可以开始调试了。 111 | 112 | ![ts1](pic/ts6.png) 113 | 114 | 点击设置按键后,软件自动与DengFOC通讯,得到界面如下: 115 | 116 | ![ts1](pic/ts7.png) 117 | 118 | 其中: 119 | 120 | **Start**:可以在可视化图表显示各个参数的波形。 121 | 122 | **Disable**:按下后会变成Enable,是用来打开或者关闭电机的按钮,这个在调参时可以用于开启和关闭电机,防止电机在不需要的时候乱动。 123 | 124 | **View all**:如果你放大了波形图然后想让波形图的大小恢复原样,就可以点击这个按钮。 125 | 126 | 在调试时,我们先点击 **Start** 按键,使得软件将点击的参数显示出来,接着,点击**Disable**先禁止电机,防止电机乱动影响调试观测。在完成这一步后,下图便是调试时需要操作主要界面部分: 127 | 128 | ![ts1](pic/ts8.png) 129 | 130 | 期望角度就是他设置的平衡时的角度,在调试时,我们需要将莱洛三角形扶起,使它保持垂直于桌面,如下图所示: 131 | 132 | ![ts1](pic/ts9.jpg) 133 | 134 | ![ts1](pic/ts10.png) 135 | 136 | 如上图,黄色波形所显示的就是莱洛三角形当前储存的期望角度,橙色的波形就是目前所在的角度,将软件中的**期望角度**设置为橙色的角度后,就完成了莱洛三角形的角度标定。 137 | 138 | 摇摆电压控制的是莱洛三角形左右摇摆的电压,电压越大就能经过越少次摆动到达平衡,但是摇摆电压过大会翻跟头。 139 | 140 | 摇摆角度是离平衡状态还差多少度时,切换到自平衡控制。 141 | 142 | 理论上,你只需要设置好**期望角度**,即可正常使用该莱洛三角形,其它的参数如摇摆电压,摇摆角度等,在程序中已经预设了我们调到的最佳参数值,除非更改机械结构或特殊情况,否则无需设置。 143 | 144 | 完成设置好**期望角度**之后,电机电机的状态按钮,使其由**Disable**变为**Ensable**,此时电机开始转动,在你设置的期望角度处将为自动自平衡稳当当的立住。 145 | 146 | 如果此时将莱洛三角形推倒,莱洛三角形将会摇晃,并努力使得自己回到能够自稳定的位置,当到达能自稳定的位置后,三角形将重新自平衡立住。 147 | 148 | ## 6 其它注意事项 149 | 150 | 如果更换为其他电机,需要重新设置电机极对数 151 | 152 | 如果自稳效果与倾倒方向相反,证明电机三相线接反,导致电机转向接反,调换三相线中其中两根即可 153 | 154 | ## 7 致谢 155 | 156 | 感谢 45 同学开源的[莱洛三角形项目](https://gitee.com/coll45/foc),也感谢他在我将莱洛三角形项目应用在 DengFOC 过程中所给予的支持。 157 | 158 | -------------------------------------------------------------------------------- /pic/effect.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/effect.gif -------------------------------------------------------------------------------- /pic/effect2.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/effect2.gif -------------------------------------------------------------------------------- /pic/jxbz1.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/jxbz1.jpg -------------------------------------------------------------------------------- /pic/jxbz2.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/jxbz2.jpg -------------------------------------------------------------------------------- /pic/jxbz3.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/jxbz3.jpg -------------------------------------------------------------------------------- /pic/jxbz4.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/jxbz4.jpg -------------------------------------------------------------------------------- /pic/jxbz5.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/jxbz5.jpg -------------------------------------------------------------------------------- /pic/jxbz6.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/jxbz6.jpg -------------------------------------------------------------------------------- /pic/jxbz7.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/jxbz7.jpg -------------------------------------------------------------------------------- /pic/jxk.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/jxk.png -------------------------------------------------------------------------------- /pic/ts1.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts1.png -------------------------------------------------------------------------------- /pic/ts10.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts10.png -------------------------------------------------------------------------------- /pic/ts2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts2.png -------------------------------------------------------------------------------- /pic/ts3.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts3.png -------------------------------------------------------------------------------- /pic/ts5.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts5.png -------------------------------------------------------------------------------- /pic/ts6.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts6.png -------------------------------------------------------------------------------- /pic/ts7.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts7.png -------------------------------------------------------------------------------- /pic/ts8.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts8.png -------------------------------------------------------------------------------- /pic/ts9.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/ts9.jpg -------------------------------------------------------------------------------- /pic/xc.jpg: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/xc.jpg -------------------------------------------------------------------------------- /pic/图片2.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/pic/图片2.png -------------------------------------------------------------------------------- /机械结构/3D打印版/centre_pan.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/机械结构/3D打印版/centre_pan.stl -------------------------------------------------------------------------------- /机械结构/3D打印版/lailuo_base2_19.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/机械结构/3D打印版/lailuo_base2_19.stl -------------------------------------------------------------------------------- /机械结构/3D打印版/lailuo_base_24.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/机械结构/3D打印版/lailuo_base_24.stl -------------------------------------------------------------------------------- /机械结构/3D打印版/triangle_bar_4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/机械结构/3D打印版/triangle_bar_4.stl -------------------------------------------------------------------------------- /机械结构/木材版/ban1.dxf: -------------------------------------------------------------------------------- 1 | 999 2 | DXF file: ban1.dxf 3 | 999 4 | Pro/ENGINEER 2014320 by Parametric Technology Corporation 5 | 0 6 | SECTION 7 | 2 8 | HEADER 9 | 9 10 | $ACADVER 11 | 1 12 | AC1021 13 | 9 14 | $DWGCODEPAGE 15 | 3 16 | ANSI_936 17 | 9 18 | $EXTMAX 19 | 10 20 | 297.0 21 | 20 22 | 210.0 23 | 30 24 | 0.0 25 | 9 26 | $EXTMIN 27 | 10 28 | 0.0 29 | 20 30 | 0.0 31 | 30 32 | 0.0 33 | 9 34 | $LIMMIN 35 | 10 36 | 0.0 37 | 20 38 | 0.0 39 | 9 40 | $LIMMAX 41 | 10 42 | 297.0 43 | 20 44 | 210.0 45 | 9 46 | $VIEWCTR 47 | 10 48 | 148.5 49 | 20 50 | 105.0 51 | 9 52 | $VIEWSIZE 53 | 40 54 | 210.0 55 | 9 56 | $CLAYER 57 | 8 58 | 0 59 | 9 60 | $LTSCALE 61 | 40 62 | 16.335 63 | 9 64 | $CELTYPE 65 | 6 66 | BYLAYER 67 | 9 68 | $DIMSCALE 69 | 40 70 | 1.0 71 | 9 72 | $DIMASZ 73 | 40 74 | 3.5 75 | 9 76 | $DIMEXO 77 | 40 78 | 1.0 79 | 9 80 | $DIMDLI 81 | 40 82 | 11.286 83 | 9 84 | $DIMEXE 85 | 40 86 | 1.5 87 | 9 88 | $DIMCEN 89 | 40 90 | 2.673 91 | 9 92 | $DIMLFAC 93 | 40 94 | 1.0 95 | 9 96 | $DIMBLK 97 | 1 98 | _FILLED 99 | 9 100 | $DIMTXT 101 | 40 102 | 3.5 103 | 9 104 | $DIMTOL 105 | 70 106 | 1 107 | 9 108 | $DIMLIM 109 | 70 110 | 0 111 | 9 112 | $DIMTFAC 113 | 40 114 | 1.0 115 | 9 116 | $DIMTP 117 | 40 118 | 0.01 119 | 9 120 | $DIMTM 121 | 40 122 | 0.01 123 | 9 124 | $DIMGAP 125 | 40 126 | 0.625 127 | 9 128 | $DIMDSEP 129 | 70 130 | 44 131 | 9 132 | $PDMODE 133 | 70 134 | 3 135 | 9 136 | $PDSIZE 137 | 40 138 | 8.0 139 | 9 140 | $HANDSEED 141 | 5 142 | 23F 143 | 9 144 | $TILEMODE 145 | 70 146 | 1 147 | 9 148 | $MEASUREMENT 149 | 70 150 | 1 151 | 9 152 | $INSUNITS 153 | 70 154 | 4 155 | 0 156 | ENDSEC 157 | 0 158 | SECTION 159 | 2 160 | CLASSES 161 | 0 162 | CLASS 163 | 1 164 | ACDBDICTIONARYWDFLT 165 | 2 166 | AcDbDictionaryWithDefault 167 | 3 168 | AutoCAD 2000 169 | 90 170 | 0 171 | 91 172 | 1 173 | 280 174 | 0 175 | 281 176 | 0 177 | 0 178 | CLASS 179 | 1 180 | ACDBPLACEHOLDER 181 | 2 182 | AcDbPlaceHolder 183 | 3 184 | AutoCAD 2000 185 | 90 186 | 0 187 | 91 188 | 1 189 | 280 190 | 0 191 | 281 192 | 0 193 | 0 194 | CLASS 195 | 1 196 | LAYOUT 197 | 2 198 | AcDbLayout 199 | 3 200 | AutoCAD 2000 201 | 90 202 | 0 203 | 91 204 | 0 205 | 280 206 | 0 207 | 281 208 | 0 209 | 0 210 | ENDSEC 211 | 0 212 | SECTION 213 | 2 214 | TABLES 215 | 0 216 | TABLE 217 | 2 218 | VPORT 219 | 5 220 | 8 221 | 100 222 | AcDbSymbolTable 223 | 70 224 | 2 225 | 0 226 | VPORT 227 | 5 228 | 1F4 229 | 100 230 | AcDbSymbolTableRecord 231 | 100 232 | AcDbViewportTableRecord 233 | 2 234 | *ACTIVE 235 | 70 236 | 0 237 | 10 238 | 0.0 239 | 20 240 | 0.0 241 | 11 242 | 1.0 243 | 21 244 | 1.0 245 | 12 246 | 148.5 247 | 22 248 | 105.0 249 | 13 250 | 0.0 251 | 23 252 | 0.0 253 | 14 254 | 1.0 255 | 24 256 | 1.0 257 | 15 258 | 0.0 259 | 25 260 | 0.0 261 | 16 262 | 0.0 263 | 26 264 | 0.0 265 | 36 266 | 1.0 267 | 17 268 | 0.0 269 | 27 270 | 0.0 271 | 37 272 | 0.0 273 | 40 274 | 210.0 275 | 41 276 | 1.4142857143 277 | 42 278 | 50.0 279 | 43 280 | 0.0 281 | 44 282 | 0.0 283 | 50 284 | 0.0 285 | 51 286 | 0.0 287 | 71 288 | 0 289 | 72 290 | 100 291 | 73 292 | 1 293 | 74 294 | 1 295 | 75 296 | 0 297 | 76 298 | 0 299 | 77 300 | 0 301 | 78 302 | 0 303 | 0 304 | ENDTAB 305 | 0 306 | TABLE 307 | 2 308 | LTYPE 309 | 5 310 | 5 311 | 100 312 | AcDbSymbolTable 313 | 70 314 | 6 315 | 0 316 | LTYPE 317 | 5 318 | 14 319 | 100 320 | AcDbSymbolTableRecord 321 | 100 322 | AcDbLinetypeTableRecord 323 | 2 324 | BYBLOCK 325 | 70 326 | 0 327 | 3 328 | 329 | 72 330 | 65 331 | 73 332 | 0 333 | 40 334 | 0.0 335 | 0 336 | LTYPE 337 | 5 338 | 15 339 | 100 340 | AcDbSymbolTableRecord 341 | 100 342 | AcDbLinetypeTableRecord 343 | 2 344 | BYLAYER 345 | 70 346 | 0 347 | 3 348 | 349 | 72 350 | 65 351 | 73 352 | 0 353 | 40 354 | 0.0 355 | 0 356 | LTYPE 357 | 5 358 | 16 359 | 100 360 | AcDbSymbolTableRecord 361 | 100 362 | AcDbLinetypeTableRecord 363 | 2 364 | CONTINUOUS 365 | 70 366 | 64 367 | 3 368 | Solid line 369 | 72 370 | 65 371 | 73 372 | 0 373 | 40 374 | 0.0 375 | 0 376 | LTYPE 377 | 5 378 | 1F5 379 | 100 380 | AcDbSymbolTableRecord 381 | 100 382 | AcDbLinetypeTableRecord 383 | 2 384 | CENTER 385 | 70 386 | 64 387 | 3 388 | ____ _ ____ _ ____ _ ____ _ ____ _ ____ _ ____ 389 | 72 390 | 65 391 | 73 392 | 4 393 | 40 394 | 0.6 395 | 49 396 | 0.375 397 | 74 398 | 0 399 | 49 400 | -0.075 401 | 74 402 | 0 403 | 49 404 | 0.075 405 | 74 406 | 0 407 | 49 408 | -0.075 409 | 74 410 | 0 411 | 0 412 | LTYPE 413 | 5 414 | 1F6 415 | 100 416 | AcDbSymbolTableRecord 417 | 100 418 | AcDbLinetypeTableRecord 419 | 2 420 | HIDDEN 421 | 70 422 | 64 423 | 3 424 | - - - - - - - - - - - - - - - - - - - - 425 | 72 426 | 65 427 | 73 428 | 2 429 | 40 430 | 0.2 431 | 49 432 | 0.1 433 | 74 434 | 0 435 | 49 436 | -0.1 437 | 74 438 | 0 439 | 0 440 | LTYPE 441 | 5 442 | 1F7 443 | 100 444 | AcDbSymbolTableRecord 445 | 100 446 | AcDbLinetypeTableRecord 447 | 2 448 | PHANTOM 449 | 70 450 | 64 451 | 3 452 | _____ _ _ _____ _ _ _____ _ _ _____ 453 | 72 454 | 65 455 | 73 456 | 6 457 | 40 458 | 0.8 459 | 49 460 | 0.45 461 | 74 462 | 0 463 | 49 464 | -0.05 465 | 74 466 | 0 467 | 49 468 | 0.1 469 | 74 470 | 0 471 | 49 472 | -0.05 473 | 74 474 | 0 475 | 49 476 | 0.1 477 | 74 478 | 0 479 | 49 480 | -0.05 481 | 74 482 | 0 483 | 0 484 | LTYPE 485 | 5 486 | 1F8 487 | 100 488 | AcDbSymbolTableRecord 489 | 100 490 | AcDbLinetypeTableRecord 491 | 2 492 | DOT 493 | 70 494 | 64 495 | 3 496 | . . . . . . . . . . . . . . . . . . . . 497 | 72 498 | 65 499 | 73 500 | 2 501 | 40 502 | 0.2 503 | 49 504 | 0.1 505 | 74 506 | 0 507 | 49 508 | -0.1 509 | 74 510 | 0 511 | 0 512 | LTYPE 513 | 5 514 | 1F9 515 | 100 516 | AcDbSymbolTableRecord 517 | 100 518 | AcDbLinetypeTableRecord 519 | 2 520 | DASHED 521 | 70 522 | 64 523 | 3 524 | - - - - - - - - - - - - - - - - - - - - 525 | 72 526 | 65 527 | 73 528 | 2 529 | 40 530 | 0.2 531 | 49 532 | 0.1 533 | 74 534 | 0 535 | 49 536 | -0.1 537 | 74 538 | 0 539 | 0 540 | ENDTAB 541 | 0 542 | TABLE 543 | 2 544 | LAYER 545 | 5 546 | 2 547 | 100 548 | AcDbSymbolTable 549 | 70 550 | 36 551 | 0 552 | LAYER 553 | 5 554 | 10 555 | 100 556 | AcDbSymbolTableRecord 557 | 100 558 | AcDbLayerTableRecord 559 | 2 560 | 0 561 | 70 562 | 0 563 | 62 564 | 7 565 | 6 566 | CONTINUOUS 567 | 370 568 | -3 569 | 390 570 | F 571 | 0 572 | LAYER 573 | 5 574 | 1FA 575 | 100 576 | AcDbSymbolTableRecord 577 | 100 578 | AcDbLayerTableRecord 579 | 2 580 | DEFAULT_1 581 | 70 582 | 0 583 | 62 584 | 7 585 | 6 586 | CENTER 587 | 370 588 | -3 589 | 390 590 | F 591 | 0 592 | LAYER 593 | 5 594 | 1FB 595 | 100 596 | AcDbSymbolTableRecord 597 | 100 598 | AcDbLayerTableRecord 599 | 2 600 | DEFAULT_2 601 | 70 602 | 0 603 | 62 604 | 8 605 | 6 606 | HIDDEN 607 | 370 608 | -3 609 | 390 610 | F 611 | 0 612 | LAYER 613 | 5 614 | 1FC 615 | 100 616 | AcDbSymbolTableRecord 617 | 100 618 | AcDbLayerTableRecord 619 | 2 620 | DEFAULT_3 621 | 70 622 | 0 623 | 62 624 | 7 625 | 6 626 | PHANTOM 627 | 370 628 | -3 629 | 390 630 | F 631 | 0 632 | LAYER 633 | 5 634 | 1FD 635 | 100 636 | AcDbSymbolTableRecord 637 | 100 638 | AcDbLayerTableRecord 639 | 2 640 | 01___PRT_ALL_DTM_PLN 641 | 70 642 | 0 643 | 62 644 | 7 645 | 6 646 | CONTINUOUS 647 | 370 648 | -3 649 | 390 650 | F 651 | 0 652 | LAYER 653 | 5 654 | 1FE 655 | 100 656 | AcDbSymbolTableRecord 657 | 100 658 | AcDbLayerTableRecord 659 | 2 660 | 01___PRT_DEF_DTM_PLN 661 | 70 662 | 0 663 | 62 664 | 7 665 | 6 666 | CONTINUOUS 667 | 370 668 | -3 669 | 390 670 | F 671 | 0 672 | LAYER 673 | 5 674 | 1FF 675 | 100 676 | AcDbSymbolTableRecord 677 | 100 678 | AcDbLayerTableRecord 679 | 2 680 | 02___PRT_ALL_AXES 681 | 70 682 | 0 683 | 62 684 | 7 685 | 6 686 | CONTINUOUS 687 | 370 688 | -3 689 | 390 690 | F 691 | 0 692 | LAYER 693 | 5 694 | 200 695 | 100 696 | AcDbSymbolTableRecord 697 | 100 698 | AcDbLayerTableRecord 699 | 2 700 | 03___PRT_ALL_CURVES 701 | 70 702 | 0 703 | 62 704 | 7 705 | 6 706 | CONTINUOUS 707 | 370 708 | -3 709 | 390 710 | F 711 | 0 712 | LAYER 713 | 5 714 | 201 715 | 100 716 | AcDbSymbolTableRecord 717 | 100 718 | AcDbLayerTableRecord 719 | 2 720 | 04___PRT_ALL_DTM_PNT 721 | 70 722 | 0 723 | 62 724 | 7 725 | 6 726 | CONTINUOUS 727 | 370 728 | -3 729 | 390 730 | F 731 | 0 732 | LAYER 733 | 5 734 | 202 735 | 100 736 | AcDbSymbolTableRecord 737 | 100 738 | AcDbLayerTableRecord 739 | 2 740 | 05___PRT_ALL_DTM_CSYS 741 | 70 742 | 0 743 | 62 744 | 7 745 | 6 746 | CONTINUOUS 747 | 370 748 | -3 749 | 390 750 | F 751 | 0 752 | LAYER 753 | 5 754 | 203 755 | 100 756 | AcDbSymbolTableRecord 757 | 100 758 | AcDbLayerTableRecord 759 | 2 760 | 05___PRT_DEF_DTM_CSYS 761 | 70 762 | 0 763 | 62 764 | 7 765 | 6 766 | CONTINUOUS 767 | 370 768 | -3 769 | 390 770 | F 771 | 0 772 | LAYER 773 | 5 774 | 204 775 | 100 776 | AcDbSymbolTableRecord 777 | 100 778 | AcDbLayerTableRecord 779 | 2 780 | 06___PRT_ALL_SURFS 781 | 70 782 | 0 783 | 62 784 | 7 785 | 6 786 | CONTINUOUS 787 | 370 788 | -3 789 | 390 790 | F 791 | 0 792 | ENDTAB 793 | 0 794 | TABLE 795 | 2 796 | STYLE 797 | 5 798 | 3 799 | 100 800 | AcDbSymbolTable 801 | 70 802 | 1 803 | 0 804 | STYLE 805 | 5 806 | 11 807 | 100 808 | AcDbSymbolTableRecord 809 | 100 810 | AcDbTextStyleTableRecord 811 | 2 812 | STANDARD 813 | 70 814 | 0 815 | 40 816 | 0.0 817 | 41 818 | 0.85 819 | 50 820 | 0.0 821 | 71 822 | 0 823 | 42 824 | 0.2 825 | 3 826 | txt 827 | 4 828 | 829 | 0 830 | STYLE 831 | 5 832 | 205 833 | 100 834 | AcDbSymbolTableRecord 835 | 100 836 | AcDbTextStyleTableRecord 837 | 2 838 | TEXTSTYLE_1 839 | 70 840 | 0 841 | 40 842 | 0.0 843 | 41 844 | 0.8 845 | 50 846 | 0.0 847 | 71 848 | 0 849 | 42 850 | 0.2 851 | 3 852 | gdt 853 | 4 854 | 855 | 0 856 | ENDTAB 857 | 0 858 | TABLE 859 | 2 860 | VIEW 861 | 5 862 | 6 863 | 100 864 | AcDbSymbolTable 865 | 70 866 | 0 867 | 0 868 | ENDTAB 869 | 0 870 | TABLE 871 | 2 872 | UCS 873 | 5 874 | 7 875 | 100 876 | AcDbSymbolTable 877 | 70 878 | 0 879 | 0 880 | ENDTAB 881 | 0 882 | TABLE 883 | 2 884 | APPID 885 | 5 886 | 9 887 | 100 888 | AcDbSymbolTable 889 | 70 890 | 1 891 | 0 892 | APPID 893 | 5 894 | 206 895 | 100 896 | AcDbSymbolTableRecord 897 | 100 898 | AcDbRegAppTableRecord 899 | 2 900 | ACAD 901 | 70 902 | 0 903 | 0 904 | ENDTAB 905 | 0 906 | TABLE 907 | 2 908 | BLOCK_RECORD 909 | 5 910 | 1 911 | 100 912 | AcDbSymbolTable 913 | 70 914 | 0 915 | 0 916 | BLOCK_RECORD 917 | 5 918 | 207 919 | 100 920 | AcDbSymbolTableRecord 921 | 100 922 | AcDbBlockTableRecord 923 | 2 924 | *Model_Space 925 | 0 926 | BLOCK_RECORD 927 | 5 928 | 208 929 | 100 930 | AcDbSymbolTableRecord 931 | 100 932 | AcDbBlockTableRecord 933 | 2 934 | *Paper_Space 935 | 0 936 | ENDTAB 937 | 0 938 | TABLE 939 | 2 940 | DIMSTYLE 941 | 5 942 | A 943 | 100 944 | AcDbSymbolTable 945 | 70 946 | 1 947 | 100 948 | AcDbDimStyleTable 949 | 71 950 | 0 951 | 0 952 | DIMSTYLE 953 | 105 954 | 209 955 | 100 956 | AcDbSymbolTableRecord 957 | 100 958 | AcDbDimStyleTableRecord 959 | 2 960 | STANDARD 961 | 70 962 | 0 963 | 3 964 | 965 | 4 966 | 967 | 40 968 | 1.0 969 | 41 970 | 3.5 971 | 42 972 | 1.0 973 | 43 974 | 0.38 975 | 44 976 | 1.5 977 | 45 978 | 0.0 979 | 46 980 | 0.0 981 | 47 982 | 0.01 983 | 48 984 | 0.01 985 | 140 986 | 3.5 987 | 141 988 | 0.09 989 | 142 990 | 0.0 991 | 143 992 | 25.4 993 | 144 994 | 1.0 995 | 145 996 | 0.0 997 | 146 998 | 1.0 999 | 147 1000 | 0.625 1001 | 71 1002 | 1.0 1003 | 72 1004 | 0.0 1005 | 73 1006 | 0 1007 | 74 1008 | 0 1009 | 75 1010 | 0 1011 | 76 1012 | 0 1013 | 77 1014 | 1 1015 | 78 1016 | 8 1017 | 170 1018 | 0 1019 | 171 1020 | 2 1021 | 172 1022 | 0 1023 | 173 1024 | 0 1025 | 174 1026 | 0 1027 | 175 1028 | 0 1029 | 176 1030 | 0 1031 | 177 1032 | 0 1033 | 178 1034 | 0 1035 | 270 1036 | 2 1037 | 271 1038 | 2 1039 | 272 1040 | 2 1041 | 273 1042 | 2 1043 | 274 1044 | 2 1045 | 275 1046 | 0 1047 | 280 1048 | 0 1049 | 281 1050 | 0 1051 | 282 1052 | 0 1053 | 283 1054 | 1 1055 | 284 1056 | 8 1057 | 285 1058 | 0 1059 | 286 1060 | 0 1061 | 287 1062 | 3 1063 | 288 1064 | 0 1065 | 340 1066 | 11 1067 | 278 1068 | 44 1069 | 0 1070 | ENDTAB 1071 | 0 1072 | ENDSEC 1073 | 0 1074 | SECTION 1075 | 2 1076 | BLOCKS 1077 | 0 1078 | BLOCK 1079 | 5 1080 | 20 1081 | 100 1082 | AcDbEntity 1083 | 8 1084 | 0 1085 | 100 1086 | AcDbBlockBegin 1087 | 2 1088 | *Model_Space 1089 | 70 1090 | 0 1091 | 10 1092 | 0.0 1093 | 20 1094 | 0.0 1095 | 30 1096 | 0.0 1097 | 3 1098 | *Model_Space 1099 | 1 1100 | 1101 | 0 1102 | ENDBLK 1103 | 5 1104 | 21 1105 | 100 1106 | AcDbEntity 1107 | 8 1108 | 0 1109 | 100 1110 | AcDbBlockEnd 1111 | 0 1112 | BLOCK 1113 | 5 1114 | 1C 1115 | 100 1116 | AcDbEntity 1117 | 8 1118 | 0 1119 | 100 1120 | AcDbBlockBegin 1121 | 2 1122 | *Paper_Space 1123 | 70 1124 | 0 1125 | 10 1126 | 0.0 1127 | 20 1128 | 0.0 1129 | 30 1130 | 0.0 1131 | 3 1132 | *Paper_Space 1133 | 1 1134 | 1135 | 0 1136 | ENDBLK 1137 | 5 1138 | 1D 1139 | 100 1140 | AcDbEntity 1141 | 8 1142 | 0 1143 | 100 1144 | AcDbBlockEnd 1145 | 0 1146 | ENDSEC 1147 | 0 1148 | SECTION 1149 | 2 1150 | ENTITIES 1151 | 0 1152 | LINE 1153 | 5 1154 | 20A 1155 | 100 1156 | AcDbEntity 1157 | 8 1158 | 0 1159 | 100 1160 | AcDbLine 1161 | 62 1162 | 7 1163 | 6 1164 | CONTINUOUS 1165 | 10 1166 | 0.0 1167 | 20 1168 | 0.0 1169 | 11 1170 | 0.0 1171 | 21 1172 | 210.0 1173 | 0 1174 | LINE 1175 | 5 1176 | 20B 1177 | 100 1178 | AcDbEntity 1179 | 8 1180 | 0 1181 | 100 1182 | AcDbLine 1183 | 62 1184 | 7 1185 | 6 1186 | CONTINUOUS 1187 | 10 1188 | 0.0 1189 | 20 1190 | 0.0 1191 | 11 1192 | 297.0 1193 | 21 1194 | 0.0 1195 | 0 1196 | LINE 1197 | 5 1198 | 20C 1199 | 100 1200 | AcDbEntity 1201 | 8 1202 | 0 1203 | 100 1204 | AcDbLine 1205 | 62 1206 | 7 1207 | 6 1208 | CONTINUOUS 1209 | 10 1210 | 0.0 1211 | 20 1212 | 210.0 1213 | 11 1214 | 297.0 1215 | 21 1216 | 210.0 1217 | 0 1218 | LINE 1219 | 5 1220 | 20D 1221 | 100 1222 | AcDbEntity 1223 | 8 1224 | 0 1225 | 100 1226 | AcDbLine 1227 | 62 1228 | 7 1229 | 6 1230 | CONTINUOUS 1231 | 10 1232 | 297.0 1233 | 20 1234 | 0.0 1235 | 11 1236 | 297.0 1237 | 21 1238 | 210.0 1239 | 0 1240 | LINE 1241 | 5 1242 | 20E 1243 | 100 1244 | AcDbEntity 1245 | 8 1246 | 0 1247 | 100 1248 | AcDbLine 1249 | 62 1250 | 7 1251 | 6 1252 | CONTINUOUS 1253 | 10 1254 | 183.0535888813 1255 | 20 1256 | 81.3281408498 1257 | 11 1258 | 174.1086839975 1259 | 21 1260 | 86.5281390561 1261 | 0 1262 | LINE 1263 | 5 1264 | 20F 1265 | 100 1266 | AcDbEntity 1267 | 8 1268 | 0 1269 | 100 1270 | AcDbLine 1271 | 62 1272 | 7 1273 | 6 1274 | CONTINUOUS 1275 | 10 1276 | 145.0856113032 1277 | 20 1278 | 137.6236850997 1279 | 11 1280 | 145.0856113032 1281 | 21 1282 | 147.8360204408 1283 | 0 1284 | LINE 1285 | 5 1286 | 210 1287 | 100 1288 | AcDbEntity 1289 | 8 1290 | 0 1291 | 100 1292 | AcDbLine 1293 | 62 1294 | 7 1295 | 6 1296 | CONTINUOUS 1297 | 10 1298 | 178.6319249261 1299 | 20 1300 | 94.308903254 1301 | 11 1302 | 187.5768298098 1303 | 21 1304 | 89.1089050477 1305 | 0 1306 | LINE 1307 | 5 1308 | 211 1309 | 100 1310 | AcDbEntity 1311 | 8 1312 | 0 1313 | 100 1314 | AcDbLine 1315 | 62 1316 | 7 1317 | 6 1318 | CONTINUOUS 1319 | 10 1320 | 154.0856113032 1321 | 20 1322 | 147.5596253115 1323 | 11 1324 | 154.0856113032 1325 | 21 1326 | 137.1798829741 1327 | 0 1328 | LINE 1329 | 5 1330 | 212 1331 | 100 1332 | AcDbEntity 1333 | 8 1334 | 0 1335 | 100 1336 | AcDbLine 1337 | 62 1338 | 7 1339 | 6 1340 | CONTINUOUS 1341 | 10 1342 | 120.2194735153 1343 | 20 1344 | 94.3734398643 1345 | 11 1346 | 111.3821079209 1347 | 21 1348 | 89.122070437 1349 | 0 1350 | LINE 1351 | 5 1352 | 213 1353 | 100 1354 | AcDbEntity 1355 | 8 1356 | 0 1357 | 100 1358 | AcDbLine 1359 | 62 1360 | 7 1361 | 6 1362 | CONTINUOUS 1363 | 10 1364 | 124.7875113191 1365 | 20 1366 | 86.6188148149 1367 | 11 1368 | 115.9806334747 1369 | 21 1370 | 81.385561922 1371 | 0 1372 | ARC 1373 | 5 1374 | 214 1375 | 100 1376 | AcDbEntity 1377 | 8 1378 | 0 1379 | 100 1380 | AcDbCircle 1381 | 62 1382 | 7 1383 | 6 1384 | CONTINUOUS 1385 | 10 1386 | -3.4791460405 1387 | 20 1388 | 75.7283867438 1389 | 40 1390 | 102.4705063953 1391 | 100 1392 | AcDbArc 1393 | 50 1394 | 0.4617427633 1395 | 51 1396 | 1.3929959874 1397 | 0 1398 | ARC 1399 | 5 1400 | 215 1401 | 100 1402 | AcDbEntity 1403 | 8 1404 | 0 1405 | 100 1406 | AcDbCircle 1407 | 62 1408 | 7 1409 | 6 1410 | CONTINUOUS 1411 | 10 1412 | 101.4592299676 1413 | 20 1414 | 78.585353882 1415 | 40 1416 | 98.7554256454 1417 | 100 1418 | AcDbArc 1419 | 50 1420 | 359.8290072522 1421 | 51 1422 | 59.8289383602 1423 | 0 1424 | ARC 1425 | 5 1426 | 216 1427 | 100 1428 | AcDbEntity 1429 | 8 1430 | 0 1431 | 100 1432 | AcDbCircle 1433 | 62 1434 | 7 1435 | 6 1436 | CONTINUOUS 1437 | 10 1438 | 101.4592299676 1439 | 20 1440 | 78.585353882 1441 | 40 1442 | 86.7582049821 1443 | 100 1444 | AcDbArc 1445 | 50 1446 | 6.9669894327 1447 | 51 1448 | 34.6429674843 1449 | 0 1450 | ARC 1451 | 5 1452 | 217 1453 | 100 1454 | AcDbEntity 1455 | 8 1456 | 0 1457 | 100 1458 | AcDbCircle 1459 | 62 1460 | 7 1461 | 6 1462 | CONTINUOUS 1463 | 10 1464 | 101.4592299676 1465 | 20 1466 | 78.585353882 1467 | 40 1468 | 86.7582049821 1469 | 100 1470 | AcDbArc 1471 | 50 1472 | 43.7530249411 1473 | 51 1474 | 52.6568870395 1475 | 0 1476 | ARC 1477 | 5 1478 | 218 1479 | 100 1480 | AcDbEntity 1481 | 8 1482 | 0 1483 | 100 1484 | AcDbCircle 1485 | 62 1486 | 7 1487 | 6 1488 | CONTINUOUS 1489 | 10 1490 | 101.4592299676 1491 | 20 1492 | 78.585353882 1493 | 40 1494 | 78.7582049821 1495 | 100 1496 | AcDbArc 1497 | 50 1498 | 11.5161020283 1499 | 51 1500 | 35.1045906526 1501 | 0 1502 | ARC 1503 | 5 1504 | 219 1505 | 100 1506 | AcDbEntity 1507 | 8 1508 | 0 1509 | 100 1510 | AcDbCircle 1511 | 62 1512 | 7 1513 | 6 1514 | CONTINUOUS 1515 | 10 1516 | 101.4592299676 1517 | 20 1518 | 78.585353882 1519 | 40 1520 | 78.7582049821 1521 | 100 1522 | AcDbArc 1523 | 50 1524 | 43.2914017727 1525 | 51 1526 | 48.0715630361 1527 | 0 1528 | ARC 1529 | 5 1530 | 21A 1531 | 100 1532 | AcDbEntity 1533 | 8 1534 | 0 1535 | 100 1536 | AcDbCircle 1537 | 62 1538 | 7 1539 | 6 1540 | CONTINUOUS 1541 | 10 1542 | 132.6856113032 1543 | 20 1544 | 81.3711331012 1545 | 40 1546 | 7.5 1547 | 100 1548 | AcDbArc 1549 | 50 1550 | 308.2690881769 1551 | 51 1552 | 14.1418360991 1553 | 0 1554 | ARC 1555 | 5 1556 | 21B 1557 | 100 1558 | AcDbEntity 1559 | 8 1560 | 0 1561 | 100 1562 | AcDbCircle 1563 | 62 1564 | 7 1565 | 6 1566 | CONTINUOUS 1567 | 10 1568 | 132.6856113032 1569 | 20 1570 | 81.3711331012 1571 | 40 1572 | 7.5 1573 | 100 1574 | AcDbArc 1575 | 50 1576 | 142.0014508106 1577 | 51 1578 | 207.8741987328 1579 | 0 1580 | CIRCLE 1581 | 5 1582 | 21C 1583 | 100 1584 | AcDbEntity 1585 | 8 1586 | 0 1587 | 100 1588 | AcDbCircle 1589 | 62 1590 | 7 1591 | 6 1592 | CONTINUOUS 1593 | 10 1594 | 132.6856113032 1595 | 20 1596 | 81.3711331012 1597 | 40 1598 | 1.5 1599 | 0 1600 | CIRCLE 1601 | 5 1602 | 21D 1603 | 100 1604 | AcDbEntity 1605 | 8 1606 | 0 1607 | 100 1608 | AcDbCircle 1609 | 62 1610 | 7 1611 | 6 1612 | CONTINUOUS 1613 | 10 1614 | 102.8202394989 1615 | 20 1616 | 79.3711331012 1617 | 40 1618 | 1.25 1619 | 0 1620 | ARC 1621 | 5 1622 | 21E 1623 | 100 1624 | AcDbEntity 1625 | 8 1626 | 0 1627 | 100 1628 | AcDbCircle 1629 | 62 1630 | 7 1631 | 6 1632 | CONTINUOUS 1633 | 10 1634 | 194.3290115292 1635 | 20 1636 | 80.5385189363 1637 | 40 1638 | 95.3961269031 1639 | 100 1640 | AcDbArc 1641 | 50 1642 | 118.9659011092 1643 | 51 1644 | 181.3929959874 1645 | 0 1646 | ARC 1647 | 5 1648 | 21F 1649 | 100 1650 | AcDbEntity 1651 | 8 1652 | 0 1653 | 100 1654 | AcDbCircle 1655 | 62 1656 | 7 1657 | 6 1658 | CONTINUOUS 1659 | 10 1660 | 194.3290115292 1661 | 20 1662 | 80.5385189363 1663 | 40 1664 | 83.3898445529 1665 | 100 1666 | AcDbArc 1667 | 50 1668 | 126.1939425435 1669 | 51 1670 | 135.8294047672 1671 | 0 1672 | ARC 1673 | 5 1674 | 220 1675 | 100 1676 | AcDbEntity 1677 | 8 1678 | 0 1679 | 100 1680 | AcDbCircle 1681 | 62 1682 | 7 1683 | 6 1684 | CONTINUOUS 1685 | 10 1686 | 194.3290115292 1687 | 20 1688 | 80.5385189363 1689 | 40 1690 | 83.3898445529 1691 | 100 1692 | AcDbArc 1693 | 50 1694 | 145.1509890662 1695 | 51 1696 | 174.0919197491 1697 | 0 1698 | ARC 1699 | 5 1700 | 221 1701 | 100 1702 | AcDbEntity 1703 | 8 1704 | 0 1705 | 100 1706 | AcDbCircle 1707 | 62 1708 | 7 1709 | 6 1710 | CONTINUOUS 1711 | 10 1712 | 194.3290115292 1713 | 20 1714 | 80.5385189363 1715 | 40 1716 | 75.3898445529 1717 | 100 1718 | AcDbArc 1719 | 50 1720 | 130.7820540803 1721 | 51 1722 | 136.0648033448 1723 | 0 1724 | ARC 1725 | 5 1726 | 222 1727 | 100 1728 | AcDbEntity 1729 | 8 1730 | 0 1731 | 100 1732 | AcDbCircle 1733 | 62 1734 | 7 1735 | 6 1736 | CONTINUOUS 1737 | 10 1738 | 194.3290115292 1739 | 20 1740 | 80.5385189363 1741 | 40 1742 | 75.3898445529 1743 | 100 1744 | AcDbArc 1745 | 50 1746 | 144.9155904885 1747 | 51 1748 | 169.4256245276 1749 | 0 1750 | ARC 1751 | 5 1752 | 223 1753 | 100 1754 | AcDbEntity 1755 | 8 1756 | 0 1757 | 100 1758 | AcDbCircle 1759 | 62 1760 | 7 1761 | 6 1762 | CONTINUOUS 1763 | 10 1764 | 166.1856113032 1765 | 20 1766 | 81.3711331012 1767 | 40 1768 | 7.5 1769 | 100 1770 | AcDbArc 1771 | 50 1772 | 331.2693775441 1773 | 51 1774 | 37.2918093207 1775 | 0 1776 | ARC 1777 | 5 1778 | 224 1779 | 100 1780 | AcDbEntity 1781 | 8 1782 | 0 1783 | 100 1784 | AcDbCircle 1785 | 62 1786 | 7 1787 | 6 1788 | CONTINUOUS 1789 | 10 1790 | 166.1856113032 1791 | 20 1792 | 81.3711331012 1793 | 40 1794 | 7.5 1795 | 100 1796 | AcDbArc 1797 | 50 1798 | 166.1532326195 1799 | 51 1800 | 232.1756643962 1801 | 0 1802 | CIRCLE 1803 | 5 1804 | 225 1805 | 100 1806 | AcDbEntity 1807 | 8 1808 | 0 1809 | 100 1810 | AcDbCircle 1811 | 62 1812 | 7 1813 | 6 1814 | CONTINUOUS 1815 | 10 1816 | 166.1856113032 1817 | 20 1818 | 81.3711331012 1819 | 40 1820 | 1.5 1821 | 0 1822 | CIRCLE 1823 | 5 1824 | 226 1825 | 100 1826 | AcDbEntity 1827 | 8 1828 | 0 1829 | 100 1830 | AcDbCircle 1831 | 62 1832 | 7 1833 | 6 1834 | CONTINUOUS 1835 | 10 1836 | 196.3509831076 1837 | 20 1838 | 79.3711331012 1839 | 40 1840 | 1.25 1841 | 0 1842 | ARC 1843 | 5 1844 | 227 1845 | 100 1846 | AcDbEntity 1847 | 8 1848 | 0 1849 | 100 1850 | AcDbCircle 1851 | 62 1852 | 7 1853 | 6 1854 | CONTINUOUS 1855 | 10 1856 | 184.8758026042 1857 | 20 1858 | 97.6165211637 1859 | 40 1860 | 75.8763595106 1861 | 100 1862 | AcDbArc 1863 | 50 1864 | 117.7167763764 1865 | 51 1866 | 118.9659011092 1867 | 0 1868 | CIRCLE 1869 | 5 1870 | 228 1871 | 100 1872 | AcDbEntity 1873 | 8 1874 | 0 1875 | 100 1876 | AcDbCircle 1877 | 62 1878 | 7 1879 | 6 1880 | CONTINUOUS 1881 | 10 1882 | 149.5856113032 1883 | 20 1884 | 106.3711331012 1885 | 40 1886 | 20.5 1887 | 0 1888 | CIRCLE 1889 | 5 1890 | 229 1891 | 100 1892 | AcDbEntity 1893 | 8 1894 | 0 1895 | 100 1896 | AcDbCircle 1897 | 62 1898 | 7 1899 | 6 1900 | CONTINUOUS 1901 | 10 1902 | 149.5856113032 1903 | 20 1904 | 106.3711331012 1905 | 40 1906 | 20.0 1907 | 0 1908 | ARC 1909 | 5 1910 | 22A 1911 | 100 1912 | AcDbEntity 1913 | 8 1914 | 0 1915 | 100 1916 | AcDbCircle 1917 | 62 1918 | 7 1919 | 6 1920 | CONTINUOUS 1921 | 10 1922 | 134.4091402031 1923 | 20 1924 | 135.2647962135 1925 | 40 1926 | 33.1943413992 1927 | 100 1928 | AcDbArc 1929 | 50 1930 | 59.8289383602 1931 | 51 1932 | 62.7933889693 1933 | 0 1934 | ARC 1935 | 5 1936 | 22B 1937 | 100 1938 | AcDbEntity 1939 | 8 1940 | 0 1941 | 100 1942 | AcDbCircle 1943 | 62 1944 | 7 1945 | 6 1946 | CONTINUOUS 1947 | 10 1948 | 132.6856113032 1949 | 20 1950 | 131.3711331012 1951 | 40 1952 | 7.5 1953 | 100 1954 | AcDbArc 1955 | 50 1956 | 11.3514679957 1957 | 51 1958 | 75.8732556628 1959 | 0 1960 | ARC 1961 | 5 1962 | 22C 1963 | 100 1964 | AcDbEntity 1965 | 8 1966 | 0 1967 | 100 1968 | AcDbCircle 1969 | 62 1970 | 7 1971 | 6 1972 | CONTINUOUS 1973 | 10 1974 | 166.1856113032 1975 | 20 1976 | 131.3711331012 1977 | 40 1978 | 7.5 1979 | 100 1980 | AcDbArc 1981 | 50 1982 | 267.7533776364 1983 | 51 1984 | 332.4653764051 1985 | 0 1986 | ARC 1987 | 5 1988 | 22D 1989 | 100 1990 | AcDbEntity 1991 | 8 1992 | 0 1993 | 100 1994 | AcDbCircle 1995 | 62 1996 | 7 1997 | 6 1998 | CONTINUOUS 1999 | 10 2000 | 166.1856113032 2001 | 20 2002 | 131.3711331012 2003 | 40 2004 | 7.5 2005 | 100 2006 | AcDbArc 2007 | 50 2008 | 105.9306160202 2009 | 51 2010 | 170.6426147889 2011 | 0 2012 | ARC 2013 | 5 2014 | 22E 2015 | 100 2016 | AcDbEntity 2017 | 8 2018 | 0 2019 | 100 2020 | AcDbCircle 2021 | 62 2022 | 7 2023 | 6 2024 | CONTINUOUS 2025 | 10 2026 | 132.6856113032 2027 | 20 2028 | 131.3711331012 2029 | 40 2030 | 7.5 2031 | 100 2032 | AcDbArc 2033 | 50 2034 | 205.1071381705 2035 | 51 2036 | 269.6289258376 2037 | 0 2038 | CIRCLE 2039 | 5 2040 | 22F 2041 | 100 2042 | AcDbEntity 2043 | 8 2044 | 0 2045 | 100 2046 | AcDbCircle 2047 | 62 2048 | 7 2049 | 6 2050 | CONTINUOUS 2051 | 10 2052 | 132.6856113032 2053 | 20 2054 | 131.3711331012 2055 | 40 2056 | 1.5 2057 | 0 2058 | CIRCLE 2059 | 5 2060 | 230 2061 | 100 2062 | AcDbEntity 2063 | 8 2064 | 0 2065 | 100 2066 | AcDbCircle 2067 | 62 2068 | 7 2069 | 6 2070 | CONTINUOUS 2071 | 10 2072 | 166.1856113032 2073 | 20 2074 | 131.3711331012 2075 | 40 2076 | 1.5 2077 | 0 2078 | CIRCLE 2079 | 5 2080 | 231 2081 | 100 2082 | AcDbEntity 2083 | 8 2084 | 02___PRT_ALL_AXES 2085 | 100 2086 | AcDbCircle 2087 | 62 2088 | 7 2089 | 6 2090 | CONTINUOUS 2091 | 10 2092 | 149.5856113032 2093 | 20 2094 | 145.3711331012 2095 | 40 2096 | 1.5 2097 | 0 2098 | ARC 2099 | 5 2100 | 232 2101 | 100 2102 | AcDbEntity 2103 | 8 2104 | 0 2105 | 100 2106 | AcDbCircle 2107 | 62 2108 | 7 2109 | 6 2110 | CONTINUOUS 2111 | 10 2112 | 193.5191930883 2113 | 20 2114 | 238.019730503 2115 | 40 2116 | 187.1022823644 2117 | 100 2118 | AcDbArc 2119 | 50 2120 | 239.6528554402 2121 | 51 2122 | 240.1794496634 2123 | 0 2124 | ARC 2125 | 5 2126 | 233 2127 | 100 2128 | AcDbEntity 2129 | 8 2130 | 0 2131 | 100 2132 | AcDbCircle 2133 | 62 2134 | 7 2135 | 6 2136 | CONTINUOUS 2137 | 10 2138 | 130.7828016164 2139 | 20 2140 | 194.1641820063 2141 | 40 2142 | 136.5566122486 2143 | 100 2144 | AcDbArc 2145 | 50 2146 | 299.8290066161 2147 | 51 2148 | 300.5582994521 2149 | 0 2150 | ARC 2151 | 5 2152 | 234 2153 | 100 2154 | AcDbEntity 2155 | 8 2156 | 0 2157 | 100 2158 | AcDbCircle 2159 | 62 2160 | 7 2161 | 6 2162 | CONTINUOUS 2163 | 10 2164 | 149.5856113032 2165 | 20 2166 | 161.3711331012 2167 | 40 2168 | 98.7554256454 2169 | 100 2170 | AcDbArc 2171 | 50 2172 | 240.1794496634 2173 | 51 2174 | 299.8290066161 2175 | 0 2176 | ARC 2177 | 5 2178 | 235 2179 | 100 2180 | AcDbEntity 2181 | 8 2182 | 0 2183 | 100 2184 | AcDbCircle 2185 | 62 2186 | 7 2187 | 6 2188 | CONTINUOUS 2189 | 10 2190 | 149.5856113032 2191 | 20 2192 | 161.3711331012 2193 | 40 2194 | 86.7582049821 2195 | 100 2196 | AcDbArc 2197 | 50 2198 | 247.2108734485 2199 | 51 2200 | 254.2636297965 2201 | 0 2202 | ARC 2203 | 5 2204 | 236 2205 | 100 2206 | AcDbEntity 2207 | 8 2208 | 0 2209 | 100 2210 | AcDbCircle 2211 | 62 2212 | 7 2213 | 6 2214 | CONTINUOUS 2215 | 10 2216 | 149.5856113032 2217 | 20 2218 | 161.3711331012 2219 | 40 2220 | 86.7582049821 2221 | 100 2222 | AcDbArc 2223 | 50 2224 | 261.8796571132 2225 | 51 2226 | 277.9508339388 2227 | 0 2228 | ARC 2229 | 5 2230 | 237 2231 | 100 2232 | AcDbEntity 2233 | 8 2234 | 0 2235 | 100 2236 | AcDbCircle 2237 | 62 2238 | 7 2239 | 6 2240 | CONTINUOUS 2241 | 10 2242 | 149.5856113032 2243 | 20 2244 | 161.3711331012 2245 | 40 2246 | 86.7582049821 2247 | 100 2248 | AcDbArc 2249 | 50 2250 | 285.4942080014 2251 | 51 2252 | 292.6910248869 2253 | 0 2254 | ARC 2255 | 5 2256 | 238 2257 | 100 2258 | AcDbEntity 2259 | 8 2260 | 0 2261 | 100 2262 | AcDbCircle 2263 | 62 2264 | 7 2265 | 6 2266 | CONTINUOUS 2267 | 10 2268 | 149.5856113032 2269 | 20 2270 | 161.3711331012 2271 | 40 2272 | 78.7582049821 2273 | 100 2274 | AcDbArc 2275 | 50 2276 | 251.6474141928 2277 | 51 2278 | 253.1646054901 2279 | 0 2280 | ARC 2281 | 5 2282 | 239 2283 | 100 2284 | AcDbEntity 2285 | 8 2286 | 0 2287 | 100 2288 | AcDbCircle 2289 | 62 2290 | 7 2291 | 6 2292 | CONTINUOUS 2293 | 10 2294 | 149.5856113032 2295 | 20 2296 | 161.3711331012 2297 | 40 2298 | 78.7582049821 2299 | 100 2300 | AcDbArc 2301 | 50 2302 | 262.9786814196 2303 | 51 2304 | 276.7946309134 2305 | 0 2306 | ARC 2307 | 5 2308 | 23A 2309 | 100 2310 | AcDbEntity 2311 | 8 2312 | 0 2313 | 100 2314 | AcDbCircle 2315 | 62 2316 | 7 2317 | 6 2318 | CONTINUOUS 2319 | 10 2320 | 149.5856113032 2321 | 20 2322 | 161.3711331012 2323 | 40 2324 | 78.7582049821 2325 | 100 2326 | AcDbArc 2327 | 50 2328 | 286.6504110268 2329 | 51 2330 | 288.1419122913 2331 | 0 2332 | CIRCLE 2333 | 5 2334 | 23B 2335 | 100 2336 | AcDbEntity 2337 | 8 2338 | 0 2339 | 100 2340 | AcDbCircle 2341 | 62 2342 | 7 2343 | 6 2344 | CONTINUOUS 2345 | 10 2346 | 149.5856113032 2347 | 20 2348 | 160.3711331012 2349 | 40 2350 | 1.25 2351 | 0 2352 | ARC 2353 | 5 2354 | 23C 2355 | 100 2356 | AcDbEntity 2357 | 8 2358 | 0 2359 | 100 2360 | AcDbCircle 2361 | 62 2362 | 7 2363 | 6 2364 | CONTINUOUS 2365 | 10 2366 | 1521.2331966329 2367 | 20 2368 | 74.348187121 2369 | 40 2370 | 1321.0248636961 2371 | 100 2372 | AcDbArc 2373 | 50 2374 | 179.8290072522 2375 | 51 2376 | 179.9034786192 2377 | 0 2378 | ENDSEC 2379 | 0 2380 | SECTION 2381 | 2 2382 | OBJECTS 2383 | 0 2384 | DICTIONARY 2385 | 5 2386 | C 2387 | 100 2388 | AcDbDictionary 2389 | 280 2390 | 0 2391 | 281 2392 | 1 2393 | 3 2394 | ACAD_GROUP 2395 | 350 2396 | D 2397 | 3 2398 | ACAD_MLINESTYLE 2399 | 350 2400 | 17 2401 | 3 2402 | ACAD_LAYOUT 2403 | 350 2404 | 1A 2405 | 3 2406 | ACAD_PLOTSETTINGS 2407 | 350 2408 | 19 2409 | 3 2410 | ACAD_PLOTSTYLENAME 2411 | 350 2412 | E 2413 | 0 2414 | DICTIONARY 2415 | 5 2416 | D 2417 | 102 2418 | {ACAD_REACTORS 2419 | 330 2420 | C 2421 | 102 2422 | } 2423 | 100 2424 | AcDbDictionary 2425 | 280 2426 | 0 2427 | 281 2428 | 1 2429 | 0 2430 | ACDBDICTIONARYWDFLT 2431 | 5 2432 | E 2433 | 102 2434 | {ACAD_REACTORS 2435 | 330 2436 | C 2437 | 102 2438 | } 2439 | 100 2440 | AcDbDictionary 2441 | 281 2442 | 1 2443 | 3 2444 | Normal 2445 | 350 2446 | F 2447 | 100 2448 | AcDbDictionaryWithDefault 2449 | 340 2450 | F 2451 | 0 2452 | DICTIONARY 2453 | 5 2454 | 17 2455 | 102 2456 | {ACAD_REACTORS 2457 | 330 2458 | C 2459 | 102 2460 | } 2461 | 100 2462 | AcDbDictionary 2463 | 280 2464 | 0 2465 | 281 2466 | 1 2467 | 3 2468 | Standard 2469 | 350 2470 | 18 2471 | 0 2472 | DICTIONARY 2473 | 5 2474 | 19 2475 | 102 2476 | {ACAD_REACTORS 2477 | 330 2478 | C 2479 | 102 2480 | } 2481 | 100 2482 | AcDbDictionary 2483 | 281 2484 | 1 2485 | 0 2486 | DICTIONARY 2487 | 5 2488 | 1A 2489 | 102 2490 | {ACAD_REACTORS 2491 | 330 2492 | C 2493 | 102 2494 | } 2495 | 100 2496 | AcDbDictionary 2497 | 281 2498 | 1 2499 | 3 2500 | Model 2501 | 350 2502 | 23D 2503 | 3 2504 | Layout1 2505 | 350 2506 | 23E 2507 | 0 2508 | ACDBPLACEHOLDER 2509 | 5 2510 | F 2511 | 102 2512 | {ACAD_REACTORS 2513 | 330 2514 | E 2515 | 102 2516 | } 2517 | 0 2518 | MLINESTYLE 2519 | 5 2520 | 18 2521 | 102 2522 | {ACAD_REACTORS 2523 | 330 2524 | 17 2525 | 102 2526 | } 2527 | 100 2528 | AcDbMlineStyle 2529 | 2 2530 | STANDARD 2531 | 70 2532 | 0 2533 | 3 2534 | 2535 | 62 2536 | 256 2537 | 51 2538 | 90.0 2539 | 52 2540 | 90.0 2541 | 71 2542 | 2 2543 | 49 2544 | 0.5 2545 | 62 2546 | 256 2547 | 6 2548 | BYLAYER 2549 | 49 2550 | -0.5 2551 | 62 2552 | 256 2553 | 6 2554 | BYLAYER 2555 | 0 2556 | LAYOUT 2557 | 5 2558 | 23D 2559 | 102 2560 | {ACAD_REACTORS 2561 | 330 2562 | 1A 2563 | 102 2564 | } 2565 | 100 2566 | AcDbPlotSettings 2567 | 1 2568 | 2569 | 2 2570 | none_device 2571 | 4 2572 | ISO_A4_(297.00_x_210.00_MM) 2573 | 6 2574 | 2575 | 40 2576 | 0.0 2577 | 41 2578 | 0.0 2579 | 42 2580 | 0.0 2581 | 43 2582 | 0.0 2583 | 44 2584 | 297.0 2585 | 45 2586 | 210.0 2587 | 46 2588 | 0.0 2589 | 47 2590 | 0.0 2591 | 48 2592 | 0.0 2593 | 49 2594 | 0.0 2595 | 140 2596 | 0.0 2597 | 141 2598 | 0.0 2599 | 142 2600 | 1.0 2601 | 143 2602 | 1.0 2603 | 70 2604 | 1024 2605 | 72 2606 | 1 2607 | 73 2608 | 0 2609 | 74 2610 | 0 2611 | 7 2612 | 2613 | 75 2614 | 0 2615 | 147 2616 | 1.0 2617 | 148 2618 | 0.0 2619 | 149 2620 | 0.0 2621 | 100 2622 | AcDbLayout 2623 | 1 2624 | Model 2625 | 70 2626 | 0 2627 | 71 2628 | 0 2629 | 10 2630 | 0.0 2631 | 20 2632 | 0.0 2633 | 11 2634 | 297.0 2635 | 21 2636 | 210.0 2637 | 12 2638 | 0.0 2639 | 22 2640 | 0.0 2641 | 32 2642 | 0.0 2643 | 14 2644 | 0.0 2645 | 24 2646 | 0.0 2647 | 34 2648 | 0.0 2649 | 15 2650 | 0.0 2651 | 25 2652 | 0.0 2653 | 35 2654 | 0.0 2655 | 146 2656 | 0.0 2657 | 13 2658 | 0.0 2659 | 23 2660 | 0.0 2661 | 33 2662 | 0.0 2663 | 16 2664 | 1.0 2665 | 26 2666 | 0.0 2667 | 36 2668 | 0.0 2669 | 17 2670 | 0.0 2671 | 27 2672 | 1.0 2673 | 37 2674 | 0.0 2675 | 76 2676 | 0 2677 | 330 2678 | 207 2679 | 345 2680 | 0 2681 | 346 2682 | 0 2683 | 0 2684 | LAYOUT 2685 | 5 2686 | 23E 2687 | 102 2688 | {ACAD_REACTORS 2689 | 330 2690 | 1A 2691 | 102 2692 | } 2693 | 100 2694 | AcDbPlotSettings 2695 | 1 2696 | 2697 | 2 2698 | none_device 2699 | 4 2700 | ISO_A4_(297.00_x_210.00_MM) 2701 | 6 2702 | 2703 | 40 2704 | 0.0 2705 | 41 2706 | 0.0 2707 | 42 2708 | 0.0 2709 | 43 2710 | 0.0 2711 | 44 2712 | 297.0 2713 | 45 2714 | 210.0 2715 | 46 2716 | 0.0 2717 | 47 2718 | 0.0 2719 | 48 2720 | 0.0 2721 | 49 2722 | 0.0 2723 | 140 2724 | 0.0 2725 | 141 2726 | 0.0 2727 | 142 2728 | 1.0 2729 | 143 2730 | 1.0 2731 | 70 2732 | 0 2733 | 72 2734 | 1 2735 | 73 2736 | 0 2737 | 74 2738 | 0 2739 | 7 2740 | 2741 | 75 2742 | 0 2743 | 147 2744 | 1.0 2745 | 148 2746 | 0.0 2747 | 149 2748 | 0.0 2749 | 100 2750 | AcDbLayout 2751 | 1 2752 | Layout1 2753 | 70 2754 | 0 2755 | 71 2756 | 1 2757 | 10 2758 | 0.0 2759 | 20 2760 | 0.0 2761 | 11 2762 | 297.0 2763 | 21 2764 | 210.0 2765 | 12 2766 | 0.0 2767 | 22 2768 | 0.0 2769 | 32 2770 | 0.0 2771 | 14 2772 | 0.0 2773 | 24 2774 | 0.0 2775 | 34 2776 | 0.0 2777 | 15 2778 | 0.0 2779 | 25 2780 | 0.0 2781 | 35 2782 | 0.0 2783 | 146 2784 | 0.0 2785 | 13 2786 | 0.0 2787 | 23 2788 | 0.0 2789 | 33 2790 | 0.0 2791 | 16 2792 | 1.0 2793 | 26 2794 | 0.0 2795 | 36 2796 | 0.0 2797 | 17 2798 | 0.0 2799 | 27 2800 | 1.0 2801 | 37 2802 | 0.0 2803 | 76 2804 | 0 2805 | 330 2806 | 208 2807 | 345 2808 | 0 2809 | 346 2810 | 0 2811 | 0 2812 | ENDSEC 2813 | 0 2814 | EOF 2815 | -------------------------------------------------------------------------------- /机械结构/木材版/ban2.dxf: -------------------------------------------------------------------------------- 1 | 999 2 | DXF file: ban2.dxf 3 | 999 4 | Pro/ENGINEER 2014320 by Parametric Technology Corporation 5 | 0 6 | SECTION 7 | 2 8 | HEADER 9 | 9 10 | $ACADVER 11 | 1 12 | AC1021 13 | 9 14 | $DWGCODEPAGE 15 | 3 16 | ANSI_936 17 | 9 18 | $EXTMAX 19 | 10 20 | 297.0 21 | 20 22 | 210.0 23 | 30 24 | 0.0 25 | 9 26 | $EXTMIN 27 | 10 28 | 0.0 29 | 20 30 | 0.0 31 | 30 32 | 0.0 33 | 9 34 | $LIMMIN 35 | 10 36 | 0.0 37 | 20 38 | 0.0 39 | 9 40 | $LIMMAX 41 | 10 42 | 297.0 43 | 20 44 | 210.0 45 | 9 46 | $VIEWCTR 47 | 10 48 | 148.5 49 | 20 50 | 105.0 51 | 9 52 | $VIEWSIZE 53 | 40 54 | 210.0 55 | 9 56 | $CLAYER 57 | 8 58 | 0 59 | 9 60 | $LTSCALE 61 | 40 62 | 16.335 63 | 9 64 | $CELTYPE 65 | 6 66 | BYLAYER 67 | 9 68 | $DIMSCALE 69 | 40 70 | 1.0 71 | 9 72 | $DIMASZ 73 | 40 74 | 3.5 75 | 9 76 | $DIMEXO 77 | 40 78 | 1.0 79 | 9 80 | $DIMDLI 81 | 40 82 | 11.286 83 | 9 84 | $DIMEXE 85 | 40 86 | 1.5 87 | 9 88 | $DIMCEN 89 | 40 90 | 2.673 91 | 9 92 | $DIMLFAC 93 | 40 94 | 1.0 95 | 9 96 | $DIMBLK 97 | 1 98 | _FILLED 99 | 9 100 | $DIMTXT 101 | 40 102 | 3.5 103 | 9 104 | $DIMTOL 105 | 70 106 | 1 107 | 9 108 | $DIMLIM 109 | 70 110 | 0 111 | 9 112 | $DIMTFAC 113 | 40 114 | 1.0 115 | 9 116 | $DIMTP 117 | 40 118 | 0.01 119 | 9 120 | $DIMTM 121 | 40 122 | 0.01 123 | 9 124 | $DIMGAP 125 | 40 126 | 0.625 127 | 9 128 | $DIMDSEP 129 | 70 130 | 44 131 | 9 132 | $PDMODE 133 | 70 134 | 3 135 | 9 136 | $PDSIZE 137 | 40 138 | 8.0 139 | 9 140 | $HANDSEED 141 | 5 142 | 239 143 | 9 144 | $TILEMODE 145 | 70 146 | 1 147 | 9 148 | $MEASUREMENT 149 | 70 150 | 1 151 | 9 152 | $INSUNITS 153 | 70 154 | 4 155 | 0 156 | ENDSEC 157 | 0 158 | SECTION 159 | 2 160 | CLASSES 161 | 0 162 | CLASS 163 | 1 164 | ACDBDICTIONARYWDFLT 165 | 2 166 | AcDbDictionaryWithDefault 167 | 3 168 | AutoCAD 2000 169 | 90 170 | 0 171 | 91 172 | 1 173 | 280 174 | 0 175 | 281 176 | 0 177 | 0 178 | CLASS 179 | 1 180 | ACDBPLACEHOLDER 181 | 2 182 | AcDbPlaceHolder 183 | 3 184 | AutoCAD 2000 185 | 90 186 | 0 187 | 91 188 | 1 189 | 280 190 | 0 191 | 281 192 | 0 193 | 0 194 | CLASS 195 | 1 196 | LAYOUT 197 | 2 198 | AcDbLayout 199 | 3 200 | AutoCAD 2000 201 | 90 202 | 0 203 | 91 204 | 0 205 | 280 206 | 0 207 | 281 208 | 0 209 | 0 210 | ENDSEC 211 | 0 212 | SECTION 213 | 2 214 | TABLES 215 | 0 216 | TABLE 217 | 2 218 | VPORT 219 | 5 220 | 8 221 | 100 222 | AcDbSymbolTable 223 | 70 224 | 2 225 | 0 226 | VPORT 227 | 5 228 | 1F4 229 | 100 230 | AcDbSymbolTableRecord 231 | 100 232 | AcDbViewportTableRecord 233 | 2 234 | *ACTIVE 235 | 70 236 | 0 237 | 10 238 | 0.0 239 | 20 240 | 0.0 241 | 11 242 | 1.0 243 | 21 244 | 1.0 245 | 12 246 | 148.5 247 | 22 248 | 105.0 249 | 13 250 | 0.0 251 | 23 252 | 0.0 253 | 14 254 | 1.0 255 | 24 256 | 1.0 257 | 15 258 | 0.0 259 | 25 260 | 0.0 261 | 16 262 | 0.0 263 | 26 264 | 0.0 265 | 36 266 | 1.0 267 | 17 268 | 0.0 269 | 27 270 | 0.0 271 | 37 272 | 0.0 273 | 40 274 | 210.0 275 | 41 276 | 1.4142857143 277 | 42 278 | 50.0 279 | 43 280 | 0.0 281 | 44 282 | 0.0 283 | 50 284 | 0.0 285 | 51 286 | 0.0 287 | 71 288 | 0 289 | 72 290 | 100 291 | 73 292 | 1 293 | 74 294 | 1 295 | 75 296 | 0 297 | 76 298 | 0 299 | 77 300 | 0 301 | 78 302 | 0 303 | 0 304 | ENDTAB 305 | 0 306 | TABLE 307 | 2 308 | LTYPE 309 | 5 310 | 5 311 | 100 312 | AcDbSymbolTable 313 | 70 314 | 6 315 | 0 316 | LTYPE 317 | 5 318 | 14 319 | 100 320 | AcDbSymbolTableRecord 321 | 100 322 | AcDbLinetypeTableRecord 323 | 2 324 | BYBLOCK 325 | 70 326 | 0 327 | 3 328 | 329 | 72 330 | 65 331 | 73 332 | 0 333 | 40 334 | 0.0 335 | 0 336 | LTYPE 337 | 5 338 | 15 339 | 100 340 | AcDbSymbolTableRecord 341 | 100 342 | AcDbLinetypeTableRecord 343 | 2 344 | BYLAYER 345 | 70 346 | 0 347 | 3 348 | 349 | 72 350 | 65 351 | 73 352 | 0 353 | 40 354 | 0.0 355 | 0 356 | LTYPE 357 | 5 358 | 16 359 | 100 360 | AcDbSymbolTableRecord 361 | 100 362 | AcDbLinetypeTableRecord 363 | 2 364 | CONTINUOUS 365 | 70 366 | 64 367 | 3 368 | Solid line 369 | 72 370 | 65 371 | 73 372 | 0 373 | 40 374 | 0.0 375 | 0 376 | LTYPE 377 | 5 378 | 1F5 379 | 100 380 | AcDbSymbolTableRecord 381 | 100 382 | AcDbLinetypeTableRecord 383 | 2 384 | CENTER 385 | 70 386 | 64 387 | 3 388 | ____ _ ____ _ ____ _ ____ _ ____ _ ____ _ ____ 389 | 72 390 | 65 391 | 73 392 | 4 393 | 40 394 | 0.6 395 | 49 396 | 0.375 397 | 74 398 | 0 399 | 49 400 | -0.075 401 | 74 402 | 0 403 | 49 404 | 0.075 405 | 74 406 | 0 407 | 49 408 | -0.075 409 | 74 410 | 0 411 | 0 412 | LTYPE 413 | 5 414 | 1F6 415 | 100 416 | AcDbSymbolTableRecord 417 | 100 418 | AcDbLinetypeTableRecord 419 | 2 420 | HIDDEN 421 | 70 422 | 64 423 | 3 424 | - - - - - - - - - - - - - - - - - - - - 425 | 72 426 | 65 427 | 73 428 | 2 429 | 40 430 | 0.2 431 | 49 432 | 0.1 433 | 74 434 | 0 435 | 49 436 | -0.1 437 | 74 438 | 0 439 | 0 440 | LTYPE 441 | 5 442 | 1F7 443 | 100 444 | AcDbSymbolTableRecord 445 | 100 446 | AcDbLinetypeTableRecord 447 | 2 448 | PHANTOM 449 | 70 450 | 64 451 | 3 452 | _____ _ _ _____ _ _ _____ _ _ _____ 453 | 72 454 | 65 455 | 73 456 | 6 457 | 40 458 | 0.8 459 | 49 460 | 0.45 461 | 74 462 | 0 463 | 49 464 | -0.05 465 | 74 466 | 0 467 | 49 468 | 0.1 469 | 74 470 | 0 471 | 49 472 | -0.05 473 | 74 474 | 0 475 | 49 476 | 0.1 477 | 74 478 | 0 479 | 49 480 | -0.05 481 | 74 482 | 0 483 | 0 484 | LTYPE 485 | 5 486 | 1F8 487 | 100 488 | AcDbSymbolTableRecord 489 | 100 490 | AcDbLinetypeTableRecord 491 | 2 492 | DOT 493 | 70 494 | 64 495 | 3 496 | . . . . . . . . . . . . . . . . . . . . 497 | 72 498 | 65 499 | 73 500 | 2 501 | 40 502 | 0.2 503 | 49 504 | 0.1 505 | 74 506 | 0 507 | 49 508 | -0.1 509 | 74 510 | 0 511 | 0 512 | LTYPE 513 | 5 514 | 1F9 515 | 100 516 | AcDbSymbolTableRecord 517 | 100 518 | AcDbLinetypeTableRecord 519 | 2 520 | DASHED 521 | 70 522 | 64 523 | 3 524 | - - - - - - - - - - - - - - - - - - - - 525 | 72 526 | 65 527 | 73 528 | 2 529 | 40 530 | 0.2 531 | 49 532 | 0.1 533 | 74 534 | 0 535 | 49 536 | -0.1 537 | 74 538 | 0 539 | 0 540 | ENDTAB 541 | 0 542 | TABLE 543 | 2 544 | LAYER 545 | 5 546 | 2 547 | 100 548 | AcDbSymbolTable 549 | 70 550 | 36 551 | 0 552 | LAYER 553 | 5 554 | 10 555 | 100 556 | AcDbSymbolTableRecord 557 | 100 558 | AcDbLayerTableRecord 559 | 2 560 | 0 561 | 70 562 | 0 563 | 62 564 | 7 565 | 6 566 | CONTINUOUS 567 | 370 568 | -3 569 | 390 570 | F 571 | 0 572 | LAYER 573 | 5 574 | 1FA 575 | 100 576 | AcDbSymbolTableRecord 577 | 100 578 | AcDbLayerTableRecord 579 | 2 580 | DEFAULT_1 581 | 70 582 | 0 583 | 62 584 | 7 585 | 6 586 | CENTER 587 | 370 588 | -3 589 | 390 590 | F 591 | 0 592 | LAYER 593 | 5 594 | 1FB 595 | 100 596 | AcDbSymbolTableRecord 597 | 100 598 | AcDbLayerTableRecord 599 | 2 600 | DEFAULT_2 601 | 70 602 | 0 603 | 62 604 | 8 605 | 6 606 | HIDDEN 607 | 370 608 | -3 609 | 390 610 | F 611 | 0 612 | LAYER 613 | 5 614 | 1FC 615 | 100 616 | AcDbSymbolTableRecord 617 | 100 618 | AcDbLayerTableRecord 619 | 2 620 | DEFAULT_3 621 | 70 622 | 0 623 | 62 624 | 7 625 | 6 626 | PHANTOM 627 | 370 628 | -3 629 | 390 630 | F 631 | 0 632 | LAYER 633 | 5 634 | 1FD 635 | 100 636 | AcDbSymbolTableRecord 637 | 100 638 | AcDbLayerTableRecord 639 | 2 640 | 01___PRT_ALL_DTM_PLN 641 | 70 642 | 0 643 | 62 644 | 7 645 | 6 646 | CONTINUOUS 647 | 370 648 | -3 649 | 390 650 | F 651 | 0 652 | LAYER 653 | 5 654 | 1FE 655 | 100 656 | AcDbSymbolTableRecord 657 | 100 658 | AcDbLayerTableRecord 659 | 2 660 | 01___PRT_DEF_DTM_PLN 661 | 70 662 | 0 663 | 62 664 | 7 665 | 6 666 | CONTINUOUS 667 | 370 668 | -3 669 | 390 670 | F 671 | 0 672 | LAYER 673 | 5 674 | 1FF 675 | 100 676 | AcDbSymbolTableRecord 677 | 100 678 | AcDbLayerTableRecord 679 | 2 680 | 02___PRT_ALL_AXES 681 | 70 682 | 0 683 | 62 684 | 7 685 | 6 686 | CONTINUOUS 687 | 370 688 | -3 689 | 390 690 | F 691 | 0 692 | LAYER 693 | 5 694 | 200 695 | 100 696 | AcDbSymbolTableRecord 697 | 100 698 | AcDbLayerTableRecord 699 | 2 700 | 03___PRT_ALL_CURVES 701 | 70 702 | 0 703 | 62 704 | 7 705 | 6 706 | CONTINUOUS 707 | 370 708 | -3 709 | 390 710 | F 711 | 0 712 | LAYER 713 | 5 714 | 201 715 | 100 716 | AcDbSymbolTableRecord 717 | 100 718 | AcDbLayerTableRecord 719 | 2 720 | 04___PRT_ALL_DTM_PNT 721 | 70 722 | 0 723 | 62 724 | 7 725 | 6 726 | CONTINUOUS 727 | 370 728 | -3 729 | 390 730 | F 731 | 0 732 | LAYER 733 | 5 734 | 202 735 | 100 736 | AcDbSymbolTableRecord 737 | 100 738 | AcDbLayerTableRecord 739 | 2 740 | 05___PRT_ALL_DTM_CSYS 741 | 70 742 | 0 743 | 62 744 | 7 745 | 6 746 | CONTINUOUS 747 | 370 748 | -3 749 | 390 750 | F 751 | 0 752 | LAYER 753 | 5 754 | 203 755 | 100 756 | AcDbSymbolTableRecord 757 | 100 758 | AcDbLayerTableRecord 759 | 2 760 | 05___PRT_DEF_DTM_CSYS 761 | 70 762 | 0 763 | 62 764 | 7 765 | 6 766 | CONTINUOUS 767 | 370 768 | -3 769 | 390 770 | F 771 | 0 772 | LAYER 773 | 5 774 | 204 775 | 100 776 | AcDbSymbolTableRecord 777 | 100 778 | AcDbLayerTableRecord 779 | 2 780 | 06___PRT_ALL_SURFS 781 | 70 782 | 0 783 | 62 784 | 7 785 | 6 786 | CONTINUOUS 787 | 370 788 | -3 789 | 390 790 | F 791 | 0 792 | ENDTAB 793 | 0 794 | TABLE 795 | 2 796 | STYLE 797 | 5 798 | 3 799 | 100 800 | AcDbSymbolTable 801 | 70 802 | 1 803 | 0 804 | STYLE 805 | 5 806 | 11 807 | 100 808 | AcDbSymbolTableRecord 809 | 100 810 | AcDbTextStyleTableRecord 811 | 2 812 | STANDARD 813 | 70 814 | 0 815 | 40 816 | 0.0 817 | 41 818 | 0.85 819 | 50 820 | 0.0 821 | 71 822 | 0 823 | 42 824 | 0.2 825 | 3 826 | txt 827 | 4 828 | 829 | 0 830 | STYLE 831 | 5 832 | 205 833 | 100 834 | AcDbSymbolTableRecord 835 | 100 836 | AcDbTextStyleTableRecord 837 | 2 838 | TEXTSTYLE_1 839 | 70 840 | 0 841 | 40 842 | 0.0 843 | 41 844 | 0.8 845 | 50 846 | 0.0 847 | 71 848 | 0 849 | 42 850 | 0.2 851 | 3 852 | gdt 853 | 4 854 | 855 | 0 856 | ENDTAB 857 | 0 858 | TABLE 859 | 2 860 | VIEW 861 | 5 862 | 6 863 | 100 864 | AcDbSymbolTable 865 | 70 866 | 0 867 | 0 868 | ENDTAB 869 | 0 870 | TABLE 871 | 2 872 | UCS 873 | 5 874 | 7 875 | 100 876 | AcDbSymbolTable 877 | 70 878 | 0 879 | 0 880 | ENDTAB 881 | 0 882 | TABLE 883 | 2 884 | APPID 885 | 5 886 | 9 887 | 100 888 | AcDbSymbolTable 889 | 70 890 | 1 891 | 0 892 | APPID 893 | 5 894 | 206 895 | 100 896 | AcDbSymbolTableRecord 897 | 100 898 | AcDbRegAppTableRecord 899 | 2 900 | ACAD 901 | 70 902 | 0 903 | 0 904 | ENDTAB 905 | 0 906 | TABLE 907 | 2 908 | BLOCK_RECORD 909 | 5 910 | 1 911 | 100 912 | AcDbSymbolTable 913 | 70 914 | 0 915 | 0 916 | BLOCK_RECORD 917 | 5 918 | 207 919 | 100 920 | AcDbSymbolTableRecord 921 | 100 922 | AcDbBlockTableRecord 923 | 2 924 | *Model_Space 925 | 0 926 | BLOCK_RECORD 927 | 5 928 | 208 929 | 100 930 | AcDbSymbolTableRecord 931 | 100 932 | AcDbBlockTableRecord 933 | 2 934 | *Paper_Space 935 | 0 936 | ENDTAB 937 | 0 938 | TABLE 939 | 2 940 | DIMSTYLE 941 | 5 942 | A 943 | 100 944 | AcDbSymbolTable 945 | 70 946 | 1 947 | 100 948 | AcDbDimStyleTable 949 | 71 950 | 0 951 | 0 952 | DIMSTYLE 953 | 105 954 | 209 955 | 100 956 | AcDbSymbolTableRecord 957 | 100 958 | AcDbDimStyleTableRecord 959 | 2 960 | STANDARD 961 | 70 962 | 0 963 | 3 964 | 965 | 4 966 | 967 | 40 968 | 1.0 969 | 41 970 | 3.5 971 | 42 972 | 1.0 973 | 43 974 | 0.38 975 | 44 976 | 1.5 977 | 45 978 | 0.0 979 | 46 980 | 0.0 981 | 47 982 | 0.01 983 | 48 984 | 0.01 985 | 140 986 | 3.5 987 | 141 988 | 0.09 989 | 142 990 | 0.0 991 | 143 992 | 25.4 993 | 144 994 | 1.0 995 | 145 996 | 0.0 997 | 146 998 | 1.0 999 | 147 1000 | 0.625 1001 | 71 1002 | 1.0 1003 | 72 1004 | 0.0 1005 | 73 1006 | 0 1007 | 74 1008 | 0 1009 | 75 1010 | 0 1011 | 76 1012 | 0 1013 | 77 1014 | 1 1015 | 78 1016 | 8 1017 | 170 1018 | 0 1019 | 171 1020 | 2 1021 | 172 1022 | 0 1023 | 173 1024 | 0 1025 | 174 1026 | 0 1027 | 175 1028 | 0 1029 | 176 1030 | 0 1031 | 177 1032 | 0 1033 | 178 1034 | 0 1035 | 270 1036 | 2 1037 | 271 1038 | 2 1039 | 272 1040 | 2 1041 | 273 1042 | 2 1043 | 274 1044 | 2 1045 | 275 1046 | 0 1047 | 280 1048 | 0 1049 | 281 1050 | 0 1051 | 282 1052 | 0 1053 | 283 1054 | 1 1055 | 284 1056 | 8 1057 | 285 1058 | 0 1059 | 286 1060 | 0 1061 | 287 1062 | 3 1063 | 288 1064 | 0 1065 | 340 1066 | 11 1067 | 278 1068 | 44 1069 | 0 1070 | ENDTAB 1071 | 0 1072 | ENDSEC 1073 | 0 1074 | SECTION 1075 | 2 1076 | BLOCKS 1077 | 0 1078 | BLOCK 1079 | 5 1080 | 20 1081 | 100 1082 | AcDbEntity 1083 | 8 1084 | 0 1085 | 100 1086 | AcDbBlockBegin 1087 | 2 1088 | *Model_Space 1089 | 70 1090 | 0 1091 | 10 1092 | 0.0 1093 | 20 1094 | 0.0 1095 | 30 1096 | 0.0 1097 | 3 1098 | *Model_Space 1099 | 1 1100 | 1101 | 0 1102 | ENDBLK 1103 | 5 1104 | 21 1105 | 100 1106 | AcDbEntity 1107 | 8 1108 | 0 1109 | 100 1110 | AcDbBlockEnd 1111 | 0 1112 | BLOCK 1113 | 5 1114 | 1C 1115 | 100 1116 | AcDbEntity 1117 | 8 1118 | 0 1119 | 100 1120 | AcDbBlockBegin 1121 | 2 1122 | *Paper_Space 1123 | 70 1124 | 0 1125 | 10 1126 | 0.0 1127 | 20 1128 | 0.0 1129 | 30 1130 | 0.0 1131 | 3 1132 | *Paper_Space 1133 | 1 1134 | 1135 | 0 1136 | ENDBLK 1137 | 5 1138 | 1D 1139 | 100 1140 | AcDbEntity 1141 | 8 1142 | 0 1143 | 100 1144 | AcDbBlockEnd 1145 | 0 1146 | ENDSEC 1147 | 0 1148 | SECTION 1149 | 2 1150 | ENTITIES 1151 | 0 1152 | MTEXT 1153 | 5 1154 | 20A 1155 | 100 1156 | AcDbEntity 1157 | 8 1158 | 0 1159 | 100 1160 | AcDbMText 1161 | 62 1162 | 2 1163 | 6 1164 | CONTINUOUS 1165 | 7 1166 | STANDARD 1167 | 71 1168 | 3 1169 | 72 1170 | 1 1171 | 10 1172 | 150.0227050781 1173 | 20 1174 | 59.3721668921 1175 | 30 1176 | 0.0 1177 | 11 1178 | 1.0 1179 | 21 1180 | 0.0 1181 | 31 1182 | 0.0 1183 | 44 1184 | 0.9 1185 | 1 1186 | 比例 1,000 1187 | 40 1188 | 3.5 1189 | 41 1190 | 35.7 1191 | 0 1192 | LINE 1193 | 5 1194 | 20B 1195 | 100 1196 | AcDbEntity 1197 | 8 1198 | 0 1199 | 100 1200 | AcDbLine 1201 | 62 1202 | 7 1203 | 6 1204 | CONTINUOUS 1205 | 10 1206 | 0.0 1207 | 20 1208 | 0.0 1209 | 11 1210 | 0.0 1211 | 21 1212 | 210.0 1213 | 0 1214 | LINE 1215 | 5 1216 | 20C 1217 | 100 1218 | AcDbEntity 1219 | 8 1220 | 0 1221 | 100 1222 | AcDbLine 1223 | 62 1224 | 7 1225 | 6 1226 | CONTINUOUS 1227 | 10 1228 | 0.0 1229 | 20 1230 | 0.0 1231 | 11 1232 | 297.0 1233 | 21 1234 | 0.0 1235 | 0 1236 | LINE 1237 | 5 1238 | 20D 1239 | 100 1240 | AcDbEntity 1241 | 8 1242 | 0 1243 | 100 1244 | AcDbLine 1245 | 62 1246 | 7 1247 | 6 1248 | CONTINUOUS 1249 | 10 1250 | 0.0 1251 | 20 1252 | 210.0 1253 | 11 1254 | 297.0 1255 | 21 1256 | 210.0 1257 | 0 1258 | LINE 1259 | 5 1260 | 20E 1261 | 100 1262 | AcDbEntity 1263 | 8 1264 | 0 1265 | 100 1266 | AcDbLine 1267 | 62 1268 | 7 1269 | 6 1270 | CONTINUOUS 1271 | 10 1272 | 297.0 1273 | 20 1274 | 0.0 1275 | 11 1276 | 297.0 1277 | 21 1278 | 210.0 1279 | 0 1280 | LINE 1281 | 5 1282 | 20F 1283 | 100 1284 | AcDbEntity 1285 | 8 1286 | 0 1287 | 100 1288 | AcDbLine 1289 | 62 1290 | 7 1291 | 6 1292 | CONTINUOUS 1293 | 10 1294 | 183.4680988834 1295 | 20 1296 | 81.3223793541 1297 | 11 1298 | 174.5231939997 1299 | 21 1300 | 86.5223775604 1301 | 0 1302 | LINE 1303 | 5 1304 | 210 1305 | 100 1306 | AcDbEntity 1307 | 8 1308 | 0 1309 | 100 1310 | AcDbLine 1311 | 62 1312 | 7 1313 | 6 1314 | CONTINUOUS 1315 | 10 1316 | 145.5001213054 1317 | 20 1318 | 137.6179236039 1319 | 11 1320 | 145.5001213054 1321 | 21 1322 | 147.8302589451 1323 | 0 1324 | LINE 1325 | 5 1326 | 211 1327 | 100 1328 | AcDbEntity 1329 | 8 1330 | 0 1331 | 100 1332 | AcDbLine 1333 | 62 1334 | 7 1335 | 6 1336 | CONTINUOUS 1337 | 10 1338 | 148.7532115773 1339 | 20 1340 | 160.2775300995 1341 | 11 1342 | 148.7915397557 1343 | 21 1344 | 160.6844807371 1345 | 0 1346 | LINE 1347 | 5 1348 | 212 1349 | 100 1350 | AcDbEntity 1351 | 8 1352 | 0 1353 | 100 1354 | AcDbLine 1355 | 62 1356 | 7 1357 | 6 1358 | CONTINUOUS 1359 | 10 1360 | 147.5001213054 1361 | 20 1362 | 111.8425971805 1363 | 11 1364 | 147.5001213054 1365 | 21 1366 | 115.654351091 1367 | 0 1368 | LINE 1369 | 5 1370 | 213 1371 | 100 1372 | AcDbEntity 1373 | 8 1374 | 0 1375 | 100 1376 | AcDbLine 1377 | 62 1378 | 7 1379 | 6 1380 | CONTINUOUS 1381 | 10 1382 | 179.0464349282 1383 | 20 1384 | 94.3031417582 1385 | 11 1386 | 187.991339812 1387 | 21 1388 | 89.1031435519 1389 | 0 1390 | LINE 1391 | 5 1392 | 214 1393 | 100 1394 | AcDbEntity 1395 | 8 1396 | 0 1397 | 100 1398 | AcDbLine 1399 | 62 1400 | 7 1401 | 6 1402 | CONTINUOUS 1403 | 10 1404 | 152.5001213054 1405 | 20 1406 | 115.654351091 1407 | 11 1408 | 152.5001213054 1409 | 21 1410 | 111.8425971805 1411 | 0 1412 | LINE 1413 | 5 1414 | 215 1415 | 100 1416 | AcDbEntity 1417 | 8 1418 | 0 1419 | 100 1420 | AcDbLine 1421 | 62 1422 | 7 1423 | 6 1424 | CONTINUOUS 1425 | 10 1426 | 154.5001213054 1427 | 20 1428 | 147.5538638158 1429 | 11 1430 | 154.5001213054 1431 | 21 1432 | 137.1741214783 1433 | 0 1434 | LINE 1435 | 5 1436 | 216 1437 | 100 1438 | AcDbEntity 1439 | 8 1440 | 0 1441 | 100 1442 | AcDbLine 1443 | 62 1444 | 7 1445 | 6 1446 | CONTINUOUS 1447 | 10 1448 | 120.6339835174 1449 | 20 1450 | 94.3676783685 1451 | 11 1452 | 111.7966179231 1453 | 21 1454 | 89.1163089413 1455 | 0 1456 | LINE 1457 | 5 1458 | 217 1459 | 100 1460 | AcDbEntity 1461 | 8 1462 | 0 1463 | 100 1464 | AcDbLine 1465 | 62 1466 | 7 1467 | 6 1468 | CONTINUOUS 1469 | 10 1470 | 148.5001213054 1471 | 20 1472 | 116.654351091 1473 | 11 1474 | 151.5001213054 1475 | 21 1476 | 116.654351091 1477 | 0 1478 | LINE 1479 | 5 1480 | 218 1481 | 100 1482 | AcDbEntity 1483 | 8 1484 | 0 1485 | 100 1486 | AcDbLine 1487 | 62 1488 | 7 1489 | 6 1490 | CONTINUOUS 1491 | 10 1492 | 116.3951434768 1493 | 20 1494 | 81.3798004263 1495 | 11 1496 | 125.2020213212 1497 | 21 1498 | 86.6130533192 1499 | 0 1500 | ARC 1501 | 5 1502 | 219 1503 | 100 1504 | AcDbEntity 1505 | 8 1506 | 0 1507 | 100 1508 | AcDbCircle 1509 | 62 1510 | 7 1511 | 6 1512 | CONTINUOUS 1513 | 10 1514 | 101.8737399698 1515 | 20 1516 | 78.5795923863 1517 | 40 1518 | 98.7582049821 1519 | 100 1520 | AcDbArc 1521 | 50 1522 | 358.8294864118 1523 | 51 1524 | 59.8290071598 1525 | 0 1526 | ARC 1527 | 5 1528 | 21A 1529 | 100 1530 | AcDbEntity 1531 | 8 1532 | 0 1533 | 100 1534 | AcDbCircle 1535 | 62 1536 | 7 1537 | 6 1538 | CONTINUOUS 1539 | 10 1540 | 101.8737399698 1541 | 20 1542 | 78.5795923863 1543 | 40 1544 | 86.7582049821 1545 | 100 1546 | AcDbArc 1547 | 50 1548 | 6.9669894327 1549 | 51 1550 | 52.6568870395 1551 | 0 1552 | ARC 1553 | 5 1554 | 21B 1555 | 100 1556 | AcDbEntity 1557 | 8 1558 | 0 1559 | 100 1560 | AcDbCircle 1561 | 62 1562 | 7 1563 | 6 1564 | CONTINUOUS 1565 | 10 1566 | 101.8737399698 1567 | 20 1568 | 78.5795923863 1569 | 40 1570 | 78.7582049821 1571 | 100 1572 | AcDbArc 1573 | 50 1574 | 11.5161020283 1575 | 51 1576 | 48.0715630361 1577 | 0 1578 | ARC 1579 | 5 1580 | 21C 1581 | 100 1582 | AcDbEntity 1583 | 8 1584 | 0 1585 | 100 1586 | AcDbCircle 1587 | 62 1588 | 7 1589 | 6 1590 | CONTINUOUS 1591 | 10 1592 | 116.1434191697 1593 | 20 1594 | 103.1259322313 1595 | 40 1596 | 70.3654850656 1597 | 100 1598 | AcDbArc 1599 | 50 1600 | 59.8290071598 1601 | 51 1602 | 61.2126790788 1603 | 0 1604 | ARC 1605 | 5 1606 | 21D 1607 | 100 1608 | AcDbEntity 1609 | 8 1610 | 0 1611 | 100 1612 | AcDbCircle 1613 | 62 1614 | 7 1615 | 6 1616 | CONTINUOUS 1617 | 10 1618 | 109.5236009239 1619 | 20 1620 | 90.7481372308 1621 | 40 1622 | 17.3632266792 1623 | 100 1624 | AcDbArc 1625 | 50 1626 | 234.4730384694 1627 | 51 1628 | 240.1794458938 1629 | 0 1630 | ARC 1631 | 5 1632 | 21E 1633 | 100 1634 | AcDbEntity 1635 | 8 1636 | 0 1637 | 100 1638 | AcDbCircle 1639 | 62 1640 | 7 1641 | 6 1642 | CONTINUOUS 1643 | 10 1644 | 150.0001213054 1645 | 20 1646 | 106.3653716055 1647 | 40 1648 | 5.5 1649 | 100 1650 | AcDbArc 1651 | 50 1652 | 122.5789703928 1653 | 51 1654 | 57.4210296072 1655 | 0 1656 | CIRCLE 1657 | 5 1658 | 21F 1659 | 100 1660 | AcDbEntity 1661 | 8 1662 | 0 1663 | 100 1664 | AcDbCircle 1665 | 62 1666 | 7 1667 | 6 1668 | CONTINUOUS 1669 | 10 1670 | 138.5001213054 1671 | 20 1672 | 106.3653716055 1673 | 40 1674 | 1.25 1675 | 0 1676 | CIRCLE 1677 | 5 1678 | 220 1679 | 100 1680 | AcDbEntity 1681 | 8 1682 | 02___PRT_ALL_AXES 1683 | 100 1684 | AcDbCircle 1685 | 62 1686 | 7 1687 | 6 1688 | CONTINUOUS 1689 | 10 1690 | 144.3432670559 1691 | 20 1692 | 100.708517356 1693 | 40 1694 | 1.25 1695 | 0 1696 | CIRCLE 1697 | 5 1698 | 221 1699 | 100 1700 | AcDbEntity 1701 | 8 1702 | 02___PRT_ALL_AXES 1703 | 100 1704 | AcDbCircle 1705 | 62 1706 | 7 1707 | 6 1708 | CONTINUOUS 1709 | 10 1710 | 144.3432670559 1711 | 20 1712 | 112.022225855 1713 | 40 1714 | 1.25 1715 | 0 1716 | CIRCLE 1717 | 5 1718 | 222 1719 | 100 1720 | AcDbEntity 1721 | 8 1722 | 0 1723 | 100 1724 | AcDbCircle 1725 | 62 1726 | 7 1727 | 6 1728 | CONTINUOUS 1729 | 10 1730 | 103.234749501 1731 | 20 1732 | 79.3653716055 1733 | 40 1734 | 1.25 1735 | 0 1736 | ARC 1737 | 5 1738 | 223 1739 | 100 1740 | AcDbEntity 1741 | 8 1742 | 0 1743 | 100 1744 | AcDbCircle 1745 | 62 1746 | 7 1747 | 6 1748 | CONTINUOUS 1749 | 10 1750 | 146.5001213054 1751 | 20 1752 | 111.8425971805 1753 | 40 1754 | 1.0 1755 | 100 1756 | AcDbArc 1757 | 50 1758 | 302.5789703928 1759 | 51 1760 | 360.0 1761 | 0 1762 | ARC 1763 | 5 1764 | 224 1765 | 100 1766 | AcDbEntity 1767 | 8 1768 | 0 1769 | 100 1770 | AcDbCircle 1771 | 62 1772 | 7 1773 | 6 1774 | CONTINUOUS 1775 | 10 1776 | 150.0001213054 1777 | 20 1778 | 161.3653716055 1779 | 40 1780 | 98.7582049821 1781 | 100 1782 | AcDbArc 1783 | 50 1784 | 240.1794458938 1785 | 51 1786 | 299.8290071598 1787 | 0 1788 | ARC 1789 | 5 1790 | 225 1791 | 100 1792 | AcDbEntity 1793 | 8 1794 | 0 1795 | 100 1796 | AcDbCircle 1797 | 62 1798 | 7 1799 | 6 1800 | CONTINUOUS 1801 | 10 1802 | 150.0001213054 1803 | 20 1804 | 161.3653716055 1805 | 40 1806 | 86.7582049821 1807 | 100 1808 | AcDbArc 1809 | 50 1810 | 247.2108734485 1811 | 51 1812 | 292.6910248869 1813 | 0 1814 | ARC 1815 | 5 1816 | 226 1817 | 100 1818 | AcDbEntity 1819 | 8 1820 | 0 1821 | 100 1822 | AcDbCircle 1823 | 62 1824 | 7 1825 | 6 1826 | CONTINUOUS 1827 | 10 1828 | 150.0001213054 1829 | 20 1830 | 161.3653716055 1831 | 40 1832 | 78.7582049821 1833 | 100 1834 | AcDbArc 1835 | 50 1836 | 251.6474141928 1837 | 51 1838 | 288.1419122913 1839 | 0 1840 | CIRCLE 1841 | 5 1842 | 227 1843 | 100 1844 | AcDbEntity 1845 | 8 1846 | 02___PRT_ALL_AXES 1847 | 100 1848 | AcDbCircle 1849 | 62 1850 | 7 1851 | 6 1852 | CONTINUOUS 1853 | 10 1854 | 150.0001213054 1855 | 20 1856 | 132.3653716055 1857 | 40 1858 | 2.5 1859 | 0 1860 | ARC 1861 | 5 1862 | 228 1863 | 100 1864 | AcDbEntity 1865 | 8 1866 | 0 1867 | 100 1868 | AcDbCircle 1869 | 62 1870 | 7 1871 | 6 1872 | CONTINUOUS 1873 | 10 1874 | 150.0001213054 1875 | 20 1876 | 160.3653716055 1877 | 40 1878 | 1.25 1879 | 100 1880 | AcDbArc 1881 | 50 1882 | 184.0296793421 1883 | 51 1884 | 165.2093899974 1885 | 0 1886 | ARC 1887 | 5 1888 | 229 1889 | 100 1890 | AcDbEntity 1891 | 8 1892 | 0 1893 | 100 1894 | AcDbCircle 1895 | 62 1896 | 7 1897 | 6 1898 | CONTINUOUS 1899 | 10 1900 | 148.5001213054 1901 | 20 1902 | 115.654351091 1903 | 40 1904 | 1.0 1905 | 100 1906 | AcDbArc 1907 | 50 1908 | 90.0 1909 | 51 1910 | 180.0 1911 | 0 1912 | ARC 1913 | 5 1914 | 22A 1915 | 100 1916 | AcDbEntity 1917 | 8 1918 | 0 1919 | 100 1920 | AcDbCircle 1921 | 62 1922 | 7 1923 | 6 1924 | CONTINUOUS 1925 | 10 1926 | 151.5001213054 1927 | 20 1928 | 115.654351091 1929 | 40 1930 | 1.0 1931 | 100 1932 | AcDbArc 1933 | 50 1934 | 0.0 1935 | 51 1936 | 90.0 1937 | 0 1938 | ARC 1939 | 5 1940 | 22B 1941 | 100 1942 | AcDbEntity 1943 | 8 1944 | 0 1945 | 100 1946 | AcDbCircle 1947 | 62 1948 | 7 1949 | 6 1950 | CONTINUOUS 1951 | 10 1952 | 201.3728616333 1953 | 20 1954 | 68.5563120223 1955 | 40 1956 | 109.0786500174 1957 | 100 1958 | AcDbArc 1959 | 50 1960 | 118.080302488 1961 | 51 1962 | 118.9659106109 1963 | 0 1964 | ARC 1965 | 5 1966 | 22C 1967 | 100 1968 | AcDbEntity 1969 | 8 1970 | 0 1971 | 100 1972 | AcDbCircle 1973 | 62 1974 | 7 1975 | 6 1976 | CONTINUOUS 1977 | 10 1978 | 194.7435215313 1979 | 20 1980 | 80.5327574406 1981 | 40 1982 | 95.3898445529 1983 | 100 1984 | AcDbArc 1985 | 50 1986 | 118.9659106109 1987 | 51 1988 | 182.3525284534 1989 | 0 1990 | ARC 1991 | 5 1992 | 22D 1993 | 100 1994 | AcDbEntity 1995 | 8 1996 | 0 1997 | 100 1998 | AcDbCircle 1999 | 62 2000 | 7 2001 | 6 2002 | CONTINUOUS 2003 | 10 2004 | 194.7435215313 2005 | 20 2006 | 80.5327574406 2007 | 40 2008 | 83.3898445529 2009 | 100 2010 | AcDbArc 2011 | 50 2012 | 126.1939425435 2013 | 51 2014 | 174.0919197491 2015 | 0 2016 | ARC 2017 | 5 2018 | 22E 2019 | 100 2020 | AcDbEntity 2021 | 8 2022 | 0 2023 | 100 2024 | AcDbCircle 2025 | 62 2026 | 7 2027 | 6 2028 | CONTINUOUS 2029 | 10 2030 | 194.7435215313 2031 | 20 2032 | 80.5327574406 2033 | 40 2034 | 75.3898445529 2035 | 100 2036 | AcDbArc 2037 | 50 2038 | 130.7820540803 2039 | 51 2040 | 169.4256245276 2041 | 0 2042 | CIRCLE 2043 | 5 2044 | 22F 2045 | 100 2046 | AcDbEntity 2047 | 8 2048 | 0 2049 | 100 2050 | AcDbCircle 2051 | 62 2052 | 7 2053 | 6 2054 | CONTINUOUS 2055 | 10 2056 | 161.5001213054 2057 | 20 2058 | 106.3653716055 2059 | 40 2060 | 1.25 2061 | 0 2062 | CIRCLE 2063 | 5 2064 | 230 2065 | 100 2066 | AcDbEntity 2067 | 8 2068 | 02___PRT_ALL_AXES 2069 | 100 2070 | AcDbCircle 2071 | 62 2072 | 7 2073 | 6 2074 | CONTINUOUS 2075 | 10 2076 | 155.6569755549 2077 | 20 2078 | 112.022225855 2079 | 40 2080 | 1.25 2081 | 0 2082 | CIRCLE 2083 | 5 2084 | 231 2085 | 100 2086 | AcDbEntity 2087 | 8 2088 | 02___PRT_ALL_AXES 2089 | 100 2090 | AcDbCircle 2091 | 62 2092 | 7 2093 | 6 2094 | CONTINUOUS 2095 | 10 2096 | 155.6569755549 2097 | 20 2098 | 100.708517356 2099 | 40 2100 | 1.25 2101 | 0 2102 | CIRCLE 2103 | 5 2104 | 232 2105 | 100 2106 | AcDbEntity 2107 | 8 2108 | 0 2109 | 100 2110 | AcDbCircle 2111 | 62 2112 | 7 2113 | 6 2114 | CONTINUOUS 2115 | 10 2116 | 196.7654931097 2117 | 20 2118 | 79.3653716055 2119 | 40 2120 | 1.25 2121 | 0 2122 | ARC 2123 | 5 2124 | 233 2125 | 100 2126 | AcDbEntity 2127 | 8 2128 | 0 2129 | 100 2130 | AcDbCircle 2131 | 62 2132 | 7 2133 | 6 2134 | CONTINUOUS 2135 | 10 2136 | 153.5001213054 2137 | 20 2138 | 111.8425971805 2139 | 40 2140 | 1.0 2141 | 100 2142 | AcDbArc 2143 | 50 2144 | 180.0 2145 | 51 2146 | 237.4210296072 2147 | 0 2148 | ARC 2149 | 5 2150 | 234 2151 | 100 2152 | AcDbEntity 2153 | 8 2154 | 0 2155 | 100 2156 | AcDbCircle 2157 | 62 2158 | 7 2159 | 6 2160 | CONTINUOUS 2161 | 10 2162 | 151.675588317 2163 | 20 2164 | 158.4432726555 2165 | 40 2166 | 95.3898445529 2167 | 100 2168 | AcDbArc 2169 | 50 2170 | 299.8290071598 2171 | 51 2172 | 300.8643963328 2173 | 0 2174 | CIRCLE 2175 | 5 2176 | 235 2177 | 100 2178 | AcDbEntity 2179 | 8 2180 | 02___PRT_ALL_AXES 2181 | 100 2182 | AcDbCircle 2183 | 62 2184 | 7 2185 | 6 2186 | CONTINUOUS 2187 | 10 2188 | 176.8407019924 2189 | 20 2190 | 133.2059522925 2191 | 40 2192 | 1.25 2193 | 0 2194 | CIRCLE 2195 | 5 2196 | 236 2197 | 100 2198 | AcDbEntity 2199 | 8 2200 | 02___PRT_ALL_AXES 2201 | 100 2202 | AcDbCircle 2203 | 62 2204 | 7 2205 | 6 2206 | CONTINUOUS 2207 | 10 2208 | 185.1129164417 2209 | 20 2210 | 119.5103154652 2211 | 40 2212 | 1.25 2213 | 0 2214 | ENDSEC 2215 | 0 2216 | SECTION 2217 | 2 2218 | OBJECTS 2219 | 0 2220 | DICTIONARY 2221 | 5 2222 | C 2223 | 100 2224 | AcDbDictionary 2225 | 280 2226 | 0 2227 | 281 2228 | 1 2229 | 3 2230 | ACAD_GROUP 2231 | 350 2232 | D 2233 | 3 2234 | ACAD_MLINESTYLE 2235 | 350 2236 | 17 2237 | 3 2238 | ACAD_LAYOUT 2239 | 350 2240 | 1A 2241 | 3 2242 | ACAD_PLOTSETTINGS 2243 | 350 2244 | 19 2245 | 3 2246 | ACAD_PLOTSTYLENAME 2247 | 350 2248 | E 2249 | 0 2250 | DICTIONARY 2251 | 5 2252 | D 2253 | 102 2254 | {ACAD_REACTORS 2255 | 330 2256 | C 2257 | 102 2258 | } 2259 | 100 2260 | AcDbDictionary 2261 | 280 2262 | 0 2263 | 281 2264 | 1 2265 | 0 2266 | ACDBDICTIONARYWDFLT 2267 | 5 2268 | E 2269 | 102 2270 | {ACAD_REACTORS 2271 | 330 2272 | C 2273 | 102 2274 | } 2275 | 100 2276 | AcDbDictionary 2277 | 281 2278 | 1 2279 | 3 2280 | Normal 2281 | 350 2282 | F 2283 | 100 2284 | AcDbDictionaryWithDefault 2285 | 340 2286 | F 2287 | 0 2288 | DICTIONARY 2289 | 5 2290 | 17 2291 | 102 2292 | {ACAD_REACTORS 2293 | 330 2294 | C 2295 | 102 2296 | } 2297 | 100 2298 | AcDbDictionary 2299 | 280 2300 | 0 2301 | 281 2302 | 1 2303 | 3 2304 | Standard 2305 | 350 2306 | 18 2307 | 0 2308 | DICTIONARY 2309 | 5 2310 | 19 2311 | 102 2312 | {ACAD_REACTORS 2313 | 330 2314 | C 2315 | 102 2316 | } 2317 | 100 2318 | AcDbDictionary 2319 | 281 2320 | 1 2321 | 0 2322 | DICTIONARY 2323 | 5 2324 | 1A 2325 | 102 2326 | {ACAD_REACTORS 2327 | 330 2328 | C 2329 | 102 2330 | } 2331 | 100 2332 | AcDbDictionary 2333 | 281 2334 | 1 2335 | 3 2336 | Model 2337 | 350 2338 | 237 2339 | 3 2340 | Layout1 2341 | 350 2342 | 238 2343 | 0 2344 | ACDBPLACEHOLDER 2345 | 5 2346 | F 2347 | 102 2348 | {ACAD_REACTORS 2349 | 330 2350 | E 2351 | 102 2352 | } 2353 | 0 2354 | MLINESTYLE 2355 | 5 2356 | 18 2357 | 102 2358 | {ACAD_REACTORS 2359 | 330 2360 | 17 2361 | 102 2362 | } 2363 | 100 2364 | AcDbMlineStyle 2365 | 2 2366 | STANDARD 2367 | 70 2368 | 0 2369 | 3 2370 | 2371 | 62 2372 | 256 2373 | 51 2374 | 90.0 2375 | 52 2376 | 90.0 2377 | 71 2378 | 2 2379 | 49 2380 | 0.5 2381 | 62 2382 | 256 2383 | 6 2384 | BYLAYER 2385 | 49 2386 | -0.5 2387 | 62 2388 | 256 2389 | 6 2390 | BYLAYER 2391 | 0 2392 | LAYOUT 2393 | 5 2394 | 237 2395 | 102 2396 | {ACAD_REACTORS 2397 | 330 2398 | 1A 2399 | 102 2400 | } 2401 | 100 2402 | AcDbPlotSettings 2403 | 1 2404 | 2405 | 2 2406 | none_device 2407 | 4 2408 | ISO_A4_(297.00_x_210.00_MM) 2409 | 6 2410 | 2411 | 40 2412 | 0.0 2413 | 41 2414 | 0.0 2415 | 42 2416 | 0.0 2417 | 43 2418 | 0.0 2419 | 44 2420 | 297.0 2421 | 45 2422 | 210.0 2423 | 46 2424 | 0.0 2425 | 47 2426 | 0.0 2427 | 48 2428 | 0.0 2429 | 49 2430 | 0.0 2431 | 140 2432 | 0.0 2433 | 141 2434 | 0.0 2435 | 142 2436 | 1.0 2437 | 143 2438 | 1.0 2439 | 70 2440 | 1024 2441 | 72 2442 | 1 2443 | 73 2444 | 0 2445 | 74 2446 | 0 2447 | 7 2448 | 2449 | 75 2450 | 0 2451 | 147 2452 | 1.0 2453 | 148 2454 | 0.0 2455 | 149 2456 | 0.0 2457 | 100 2458 | AcDbLayout 2459 | 1 2460 | Model 2461 | 70 2462 | 0 2463 | 71 2464 | 0 2465 | 10 2466 | 0.0 2467 | 20 2468 | 0.0 2469 | 11 2470 | 297.0 2471 | 21 2472 | 210.0 2473 | 12 2474 | 0.0 2475 | 22 2476 | 0.0 2477 | 32 2478 | 0.0 2479 | 14 2480 | 0.0 2481 | 24 2482 | 0.0 2483 | 34 2484 | 0.0 2485 | 15 2486 | 0.0 2487 | 25 2488 | 0.0 2489 | 35 2490 | 0.0 2491 | 146 2492 | 0.0 2493 | 13 2494 | 0.0 2495 | 23 2496 | 0.0 2497 | 33 2498 | 0.0 2499 | 16 2500 | 1.0 2501 | 26 2502 | 0.0 2503 | 36 2504 | 0.0 2505 | 17 2506 | 0.0 2507 | 27 2508 | 1.0 2509 | 37 2510 | 0.0 2511 | 76 2512 | 0 2513 | 330 2514 | 207 2515 | 345 2516 | 0 2517 | 346 2518 | 0 2519 | 0 2520 | LAYOUT 2521 | 5 2522 | 238 2523 | 102 2524 | {ACAD_REACTORS 2525 | 330 2526 | 1A 2527 | 102 2528 | } 2529 | 100 2530 | AcDbPlotSettings 2531 | 1 2532 | 2533 | 2 2534 | none_device 2535 | 4 2536 | ISO_A4_(297.00_x_210.00_MM) 2537 | 6 2538 | 2539 | 40 2540 | 0.0 2541 | 41 2542 | 0.0 2543 | 42 2544 | 0.0 2545 | 43 2546 | 0.0 2547 | 44 2548 | 297.0 2549 | 45 2550 | 210.0 2551 | 46 2552 | 0.0 2553 | 47 2554 | 0.0 2555 | 48 2556 | 0.0 2557 | 49 2558 | 0.0 2559 | 140 2560 | 0.0 2561 | 141 2562 | 0.0 2563 | 142 2564 | 1.0 2565 | 143 2566 | 1.0 2567 | 70 2568 | 0 2569 | 72 2570 | 1 2571 | 73 2572 | 0 2573 | 74 2574 | 0 2575 | 7 2576 | 2577 | 75 2578 | 0 2579 | 147 2580 | 1.0 2581 | 148 2582 | 0.0 2583 | 149 2584 | 0.0 2585 | 100 2586 | AcDbLayout 2587 | 1 2588 | Layout1 2589 | 70 2590 | 0 2591 | 71 2592 | 1 2593 | 10 2594 | 0.0 2595 | 20 2596 | 0.0 2597 | 11 2598 | 297.0 2599 | 21 2600 | 210.0 2601 | 12 2602 | 0.0 2603 | 22 2604 | 0.0 2605 | 32 2606 | 0.0 2607 | 14 2608 | 0.0 2609 | 24 2610 | 0.0 2611 | 34 2612 | 0.0 2613 | 15 2614 | 0.0 2615 | 25 2616 | 0.0 2617 | 35 2618 | 0.0 2619 | 146 2620 | 0.0 2621 | 13 2622 | 0.0 2623 | 23 2624 | 0.0 2625 | 33 2626 | 0.0 2627 | 16 2628 | 1.0 2629 | 26 2630 | 0.0 2631 | 36 2632 | 0.0 2633 | 17 2634 | 0.0 2635 | 27 2636 | 1.0 2637 | 37 2638 | 0.0 2639 | 76 2640 | 0 2641 | 330 2642 | 208 2643 | 345 2644 | 0 2645 | 346 2646 | 0 2647 | 0 2648 | ENDSEC 2649 | 0 2650 | EOF 2651 | -------------------------------------------------------------------------------- /机械结构/木材版/lun1.dxf: -------------------------------------------------------------------------------- 1 | 999 2 | DXF file: lun1.dxf 3 | 999 4 | Pro/ENGINEER 2014320 by Parametric Technology Corporation 5 | 0 6 | SECTION 7 | 2 8 | HEADER 9 | 9 10 | $ACADVER 11 | 1 12 | AC1021 13 | 9 14 | $DWGCODEPAGE 15 | 3 16 | ANSI_936 17 | 9 18 | $EXTMAX 19 | 10 20 | 297.0 21 | 20 22 | 210.0 23 | 30 24 | 0.0 25 | 9 26 | $EXTMIN 27 | 10 28 | 0.0 29 | 20 30 | 0.0 31 | 30 32 | 0.0 33 | 9 34 | $LIMMIN 35 | 10 36 | 0.0 37 | 20 38 | 0.0 39 | 9 40 | $LIMMAX 41 | 10 42 | 297.0 43 | 20 44 | 210.0 45 | 9 46 | $VIEWCTR 47 | 10 48 | 148.5 49 | 20 50 | 105.0 51 | 9 52 | $VIEWSIZE 53 | 40 54 | 210.0 55 | 9 56 | $CLAYER 57 | 8 58 | 0 59 | 9 60 | $LTSCALE 61 | 40 62 | 16.335 63 | 9 64 | $CELTYPE 65 | 6 66 | BYLAYER 67 | 9 68 | $DIMSCALE 69 | 40 70 | 1.0 71 | 9 72 | $DIMASZ 73 | 40 74 | 3.5 75 | 9 76 | $DIMEXO 77 | 40 78 | 1.0 79 | 9 80 | $DIMDLI 81 | 40 82 | 11.286 83 | 9 84 | $DIMEXE 85 | 40 86 | 1.5 87 | 9 88 | $DIMCEN 89 | 40 90 | 2.673 91 | 9 92 | $DIMLFAC 93 | 40 94 | 1.0 95 | 9 96 | $DIMBLK 97 | 1 98 | _FILLED 99 | 9 100 | $DIMTXT 101 | 40 102 | 3.5 103 | 9 104 | $DIMTOL 105 | 70 106 | 1 107 | 9 108 | $DIMLIM 109 | 70 110 | 0 111 | 9 112 | $DIMTFAC 113 | 40 114 | 1.0 115 | 9 116 | $DIMTP 117 | 40 118 | 0.01 119 | 9 120 | $DIMTM 121 | 40 122 | 0.01 123 | 9 124 | $DIMGAP 125 | 40 126 | 0.625 127 | 9 128 | $DIMDSEP 129 | 70 130 | 44 131 | 9 132 | $PDMODE 133 | 70 134 | 3 135 | 9 136 | $PDSIZE 137 | 40 138 | 8.0 139 | 9 140 | $HANDSEED 141 | 5 142 | 22C 143 | 9 144 | $TILEMODE 145 | 70 146 | 1 147 | 9 148 | $MEASUREMENT 149 | 70 150 | 1 151 | 9 152 | $INSUNITS 153 | 70 154 | 4 155 | 0 156 | ENDSEC 157 | 0 158 | SECTION 159 | 2 160 | CLASSES 161 | 0 162 | CLASS 163 | 1 164 | ACDBDICTIONARYWDFLT 165 | 2 166 | AcDbDictionaryWithDefault 167 | 3 168 | AutoCAD 2000 169 | 90 170 | 0 171 | 91 172 | 1 173 | 280 174 | 0 175 | 281 176 | 0 177 | 0 178 | CLASS 179 | 1 180 | ACDBPLACEHOLDER 181 | 2 182 | AcDbPlaceHolder 183 | 3 184 | AutoCAD 2000 185 | 90 186 | 0 187 | 91 188 | 1 189 | 280 190 | 0 191 | 281 192 | 0 193 | 0 194 | CLASS 195 | 1 196 | LAYOUT 197 | 2 198 | AcDbLayout 199 | 3 200 | AutoCAD 2000 201 | 90 202 | 0 203 | 91 204 | 0 205 | 280 206 | 0 207 | 281 208 | 0 209 | 0 210 | ENDSEC 211 | 0 212 | SECTION 213 | 2 214 | TABLES 215 | 0 216 | TABLE 217 | 2 218 | VPORT 219 | 5 220 | 8 221 | 100 222 | AcDbSymbolTable 223 | 70 224 | 2 225 | 0 226 | VPORT 227 | 5 228 | 1F4 229 | 100 230 | AcDbSymbolTableRecord 231 | 100 232 | AcDbViewportTableRecord 233 | 2 234 | *ACTIVE 235 | 70 236 | 0 237 | 10 238 | 0.0 239 | 20 240 | 0.0 241 | 11 242 | 1.0 243 | 21 244 | 1.0 245 | 12 246 | 148.5 247 | 22 248 | 105.0 249 | 13 250 | 0.0 251 | 23 252 | 0.0 253 | 14 254 | 1.0 255 | 24 256 | 1.0 257 | 15 258 | 0.0 259 | 25 260 | 0.0 261 | 16 262 | 0.0 263 | 26 264 | 0.0 265 | 36 266 | 1.0 267 | 17 268 | 0.0 269 | 27 270 | 0.0 271 | 37 272 | 0.0 273 | 40 274 | 210.0 275 | 41 276 | 1.4142857143 277 | 42 278 | 50.0 279 | 43 280 | 0.0 281 | 44 282 | 0.0 283 | 50 284 | 0.0 285 | 51 286 | 0.0 287 | 71 288 | 0 289 | 72 290 | 100 291 | 73 292 | 1 293 | 74 294 | 1 295 | 75 296 | 0 297 | 76 298 | 0 299 | 77 300 | 0 301 | 78 302 | 0 303 | 0 304 | ENDTAB 305 | 0 306 | TABLE 307 | 2 308 | LTYPE 309 | 5 310 | 5 311 | 100 312 | AcDbSymbolTable 313 | 70 314 | 6 315 | 0 316 | LTYPE 317 | 5 318 | 14 319 | 100 320 | AcDbSymbolTableRecord 321 | 100 322 | AcDbLinetypeTableRecord 323 | 2 324 | BYBLOCK 325 | 70 326 | 0 327 | 3 328 | 329 | 72 330 | 65 331 | 73 332 | 0 333 | 40 334 | 0.0 335 | 0 336 | LTYPE 337 | 5 338 | 15 339 | 100 340 | AcDbSymbolTableRecord 341 | 100 342 | AcDbLinetypeTableRecord 343 | 2 344 | BYLAYER 345 | 70 346 | 0 347 | 3 348 | 349 | 72 350 | 65 351 | 73 352 | 0 353 | 40 354 | 0.0 355 | 0 356 | LTYPE 357 | 5 358 | 16 359 | 100 360 | AcDbSymbolTableRecord 361 | 100 362 | AcDbLinetypeTableRecord 363 | 2 364 | CONTINUOUS 365 | 70 366 | 64 367 | 3 368 | Solid line 369 | 72 370 | 65 371 | 73 372 | 0 373 | 40 374 | 0.0 375 | 0 376 | LTYPE 377 | 5 378 | 1F5 379 | 100 380 | AcDbSymbolTableRecord 381 | 100 382 | AcDbLinetypeTableRecord 383 | 2 384 | CENTER 385 | 70 386 | 64 387 | 3 388 | ____ _ ____ _ ____ _ ____ _ ____ _ ____ _ ____ 389 | 72 390 | 65 391 | 73 392 | 4 393 | 40 394 | 0.6 395 | 49 396 | 0.375 397 | 74 398 | 0 399 | 49 400 | -0.075 401 | 74 402 | 0 403 | 49 404 | 0.075 405 | 74 406 | 0 407 | 49 408 | -0.075 409 | 74 410 | 0 411 | 0 412 | LTYPE 413 | 5 414 | 1F6 415 | 100 416 | AcDbSymbolTableRecord 417 | 100 418 | AcDbLinetypeTableRecord 419 | 2 420 | HIDDEN 421 | 70 422 | 64 423 | 3 424 | - - - - - - - - - - - - - - - - - - - - 425 | 72 426 | 65 427 | 73 428 | 2 429 | 40 430 | 0.2 431 | 49 432 | 0.1 433 | 74 434 | 0 435 | 49 436 | -0.1 437 | 74 438 | 0 439 | 0 440 | LTYPE 441 | 5 442 | 1F7 443 | 100 444 | AcDbSymbolTableRecord 445 | 100 446 | AcDbLinetypeTableRecord 447 | 2 448 | PHANTOM 449 | 70 450 | 64 451 | 3 452 | _____ _ _ _____ _ _ _____ _ _ _____ 453 | 72 454 | 65 455 | 73 456 | 6 457 | 40 458 | 0.8 459 | 49 460 | 0.45 461 | 74 462 | 0 463 | 49 464 | -0.05 465 | 74 466 | 0 467 | 49 468 | 0.1 469 | 74 470 | 0 471 | 49 472 | -0.05 473 | 74 474 | 0 475 | 49 476 | 0.1 477 | 74 478 | 0 479 | 49 480 | -0.05 481 | 74 482 | 0 483 | 0 484 | LTYPE 485 | 5 486 | 1F8 487 | 100 488 | AcDbSymbolTableRecord 489 | 100 490 | AcDbLinetypeTableRecord 491 | 2 492 | DOT 493 | 70 494 | 64 495 | 3 496 | . . . . . . . . . . . . . . . . . . . . 497 | 72 498 | 65 499 | 73 500 | 2 501 | 40 502 | 0.2 503 | 49 504 | 0.1 505 | 74 506 | 0 507 | 49 508 | -0.1 509 | 74 510 | 0 511 | 0 512 | LTYPE 513 | 5 514 | 1F9 515 | 100 516 | AcDbSymbolTableRecord 517 | 100 518 | AcDbLinetypeTableRecord 519 | 2 520 | DASHED 521 | 70 522 | 64 523 | 3 524 | - - - - - - - - - - - - - - - - - - - - 525 | 72 526 | 65 527 | 73 528 | 2 529 | 40 530 | 0.2 531 | 49 532 | 0.1 533 | 74 534 | 0 535 | 49 536 | -0.1 537 | 74 538 | 0 539 | 0 540 | ENDTAB 541 | 0 542 | TABLE 543 | 2 544 | LAYER 545 | 5 546 | 2 547 | 100 548 | AcDbSymbolTable 549 | 70 550 | 36 551 | 0 552 | LAYER 553 | 5 554 | 10 555 | 100 556 | AcDbSymbolTableRecord 557 | 100 558 | AcDbLayerTableRecord 559 | 2 560 | 0 561 | 70 562 | 0 563 | 62 564 | 7 565 | 6 566 | CONTINUOUS 567 | 370 568 | -3 569 | 390 570 | F 571 | 0 572 | LAYER 573 | 5 574 | 1FA 575 | 100 576 | AcDbSymbolTableRecord 577 | 100 578 | AcDbLayerTableRecord 579 | 2 580 | DEFAULT_1 581 | 70 582 | 0 583 | 62 584 | 7 585 | 6 586 | CENTER 587 | 370 588 | -3 589 | 390 590 | F 591 | 0 592 | LAYER 593 | 5 594 | 1FB 595 | 100 596 | AcDbSymbolTableRecord 597 | 100 598 | AcDbLayerTableRecord 599 | 2 600 | DEFAULT_2 601 | 70 602 | 0 603 | 62 604 | 8 605 | 6 606 | HIDDEN 607 | 370 608 | -3 609 | 390 610 | F 611 | 0 612 | LAYER 613 | 5 614 | 1FC 615 | 100 616 | AcDbSymbolTableRecord 617 | 100 618 | AcDbLayerTableRecord 619 | 2 620 | DEFAULT_3 621 | 70 622 | 0 623 | 62 624 | 7 625 | 6 626 | PHANTOM 627 | 370 628 | -3 629 | 390 630 | F 631 | 0 632 | LAYER 633 | 5 634 | 1FD 635 | 100 636 | AcDbSymbolTableRecord 637 | 100 638 | AcDbLayerTableRecord 639 | 2 640 | 01___PRT_ALL_DTM_PLN 641 | 70 642 | 0 643 | 62 644 | 7 645 | 6 646 | CONTINUOUS 647 | 370 648 | -3 649 | 390 650 | F 651 | 0 652 | LAYER 653 | 5 654 | 1FE 655 | 100 656 | AcDbSymbolTableRecord 657 | 100 658 | AcDbLayerTableRecord 659 | 2 660 | 01___PRT_DEF_DTM_PLN 661 | 70 662 | 0 663 | 62 664 | 7 665 | 6 666 | CONTINUOUS 667 | 370 668 | -3 669 | 390 670 | F 671 | 0 672 | LAYER 673 | 5 674 | 1FF 675 | 100 676 | AcDbSymbolTableRecord 677 | 100 678 | AcDbLayerTableRecord 679 | 2 680 | 02___PRT_ALL_AXES 681 | 70 682 | 0 683 | 62 684 | 7 685 | 6 686 | CONTINUOUS 687 | 370 688 | -3 689 | 390 690 | F 691 | 0 692 | LAYER 693 | 5 694 | 200 695 | 100 696 | AcDbSymbolTableRecord 697 | 100 698 | AcDbLayerTableRecord 699 | 2 700 | 03___PRT_ALL_CURVES 701 | 70 702 | 0 703 | 62 704 | 7 705 | 6 706 | CONTINUOUS 707 | 370 708 | -3 709 | 390 710 | F 711 | 0 712 | LAYER 713 | 5 714 | 201 715 | 100 716 | AcDbSymbolTableRecord 717 | 100 718 | AcDbLayerTableRecord 719 | 2 720 | 04___PRT_ALL_DTM_PNT 721 | 70 722 | 0 723 | 62 724 | 7 725 | 6 726 | CONTINUOUS 727 | 370 728 | -3 729 | 390 730 | F 731 | 0 732 | LAYER 733 | 5 734 | 202 735 | 100 736 | AcDbSymbolTableRecord 737 | 100 738 | AcDbLayerTableRecord 739 | 2 740 | 05___PRT_ALL_DTM_CSYS 741 | 70 742 | 0 743 | 62 744 | 7 745 | 6 746 | CONTINUOUS 747 | 370 748 | -3 749 | 390 750 | F 751 | 0 752 | LAYER 753 | 5 754 | 203 755 | 100 756 | AcDbSymbolTableRecord 757 | 100 758 | AcDbLayerTableRecord 759 | 2 760 | 05___PRT_DEF_DTM_CSYS 761 | 70 762 | 0 763 | 62 764 | 7 765 | 6 766 | CONTINUOUS 767 | 370 768 | -3 769 | 390 770 | F 771 | 0 772 | LAYER 773 | 5 774 | 204 775 | 100 776 | AcDbSymbolTableRecord 777 | 100 778 | AcDbLayerTableRecord 779 | 2 780 | 06___PRT_ALL_SURFS 781 | 70 782 | 0 783 | 62 784 | 7 785 | 6 786 | CONTINUOUS 787 | 370 788 | -3 789 | 390 790 | F 791 | 0 792 | ENDTAB 793 | 0 794 | TABLE 795 | 2 796 | STYLE 797 | 5 798 | 3 799 | 100 800 | AcDbSymbolTable 801 | 70 802 | 1 803 | 0 804 | STYLE 805 | 5 806 | 11 807 | 100 808 | AcDbSymbolTableRecord 809 | 100 810 | AcDbTextStyleTableRecord 811 | 2 812 | STANDARD 813 | 70 814 | 0 815 | 40 816 | 0.0 817 | 41 818 | 0.85 819 | 50 820 | 0.0 821 | 71 822 | 0 823 | 42 824 | 0.2 825 | 3 826 | txt 827 | 4 828 | 829 | 0 830 | STYLE 831 | 5 832 | 205 833 | 100 834 | AcDbSymbolTableRecord 835 | 100 836 | AcDbTextStyleTableRecord 837 | 2 838 | TEXTSTYLE_1 839 | 70 840 | 0 841 | 40 842 | 0.0 843 | 41 844 | 0.8 845 | 50 846 | 0.0 847 | 71 848 | 0 849 | 42 850 | 0.2 851 | 3 852 | gdt 853 | 4 854 | 855 | 0 856 | ENDTAB 857 | 0 858 | TABLE 859 | 2 860 | VIEW 861 | 5 862 | 6 863 | 100 864 | AcDbSymbolTable 865 | 70 866 | 0 867 | 0 868 | ENDTAB 869 | 0 870 | TABLE 871 | 2 872 | UCS 873 | 5 874 | 7 875 | 100 876 | AcDbSymbolTable 877 | 70 878 | 0 879 | 0 880 | ENDTAB 881 | 0 882 | TABLE 883 | 2 884 | APPID 885 | 5 886 | 9 887 | 100 888 | AcDbSymbolTable 889 | 70 890 | 1 891 | 0 892 | APPID 893 | 5 894 | 206 895 | 100 896 | AcDbSymbolTableRecord 897 | 100 898 | AcDbRegAppTableRecord 899 | 2 900 | ACAD 901 | 70 902 | 0 903 | 0 904 | ENDTAB 905 | 0 906 | TABLE 907 | 2 908 | BLOCK_RECORD 909 | 5 910 | 1 911 | 100 912 | AcDbSymbolTable 913 | 70 914 | 0 915 | 0 916 | BLOCK_RECORD 917 | 5 918 | 207 919 | 100 920 | AcDbSymbolTableRecord 921 | 100 922 | AcDbBlockTableRecord 923 | 2 924 | *Model_Space 925 | 0 926 | BLOCK_RECORD 927 | 5 928 | 208 929 | 100 930 | AcDbSymbolTableRecord 931 | 100 932 | AcDbBlockTableRecord 933 | 2 934 | *Paper_Space 935 | 0 936 | ENDTAB 937 | 0 938 | TABLE 939 | 2 940 | DIMSTYLE 941 | 5 942 | A 943 | 100 944 | AcDbSymbolTable 945 | 70 946 | 1 947 | 100 948 | AcDbDimStyleTable 949 | 71 950 | 0 951 | 0 952 | DIMSTYLE 953 | 105 954 | 209 955 | 100 956 | AcDbSymbolTableRecord 957 | 100 958 | AcDbDimStyleTableRecord 959 | 2 960 | STANDARD 961 | 70 962 | 0 963 | 3 964 | 965 | 4 966 | 967 | 40 968 | 1.0 969 | 41 970 | 3.5 971 | 42 972 | 1.0 973 | 43 974 | 0.38 975 | 44 976 | 1.5 977 | 45 978 | 0.0 979 | 46 980 | 0.0 981 | 47 982 | 0.01 983 | 48 984 | 0.01 985 | 140 986 | 3.5 987 | 141 988 | 0.09 989 | 142 990 | 0.0 991 | 143 992 | 25.4 993 | 144 994 | 1.0 995 | 145 996 | 0.0 997 | 146 998 | 1.0 999 | 147 1000 | 0.625 1001 | 71 1002 | 1.0 1003 | 72 1004 | 0.0 1005 | 73 1006 | 0 1007 | 74 1008 | 0 1009 | 75 1010 | 0 1011 | 76 1012 | 0 1013 | 77 1014 | 1 1015 | 78 1016 | 8 1017 | 170 1018 | 0 1019 | 171 1020 | 2 1021 | 172 1022 | 0 1023 | 173 1024 | 0 1025 | 174 1026 | 0 1027 | 175 1028 | 0 1029 | 176 1030 | 0 1031 | 177 1032 | 0 1033 | 178 1034 | 0 1035 | 270 1036 | 2 1037 | 271 1038 | 2 1039 | 272 1040 | 2 1041 | 273 1042 | 2 1043 | 274 1044 | 2 1045 | 275 1046 | 0 1047 | 280 1048 | 0 1049 | 281 1050 | 0 1051 | 282 1052 | 0 1053 | 283 1054 | 1 1055 | 284 1056 | 8 1057 | 285 1058 | 0 1059 | 286 1060 | 0 1061 | 287 1062 | 3 1063 | 288 1064 | 0 1065 | 340 1066 | 11 1067 | 278 1068 | 44 1069 | 0 1070 | ENDTAB 1071 | 0 1072 | ENDSEC 1073 | 0 1074 | SECTION 1075 | 2 1076 | BLOCKS 1077 | 0 1078 | BLOCK 1079 | 5 1080 | 20 1081 | 100 1082 | AcDbEntity 1083 | 8 1084 | 0 1085 | 100 1086 | AcDbBlockBegin 1087 | 2 1088 | *Model_Space 1089 | 70 1090 | 0 1091 | 10 1092 | 0.0 1093 | 20 1094 | 0.0 1095 | 30 1096 | 0.0 1097 | 3 1098 | *Model_Space 1099 | 1 1100 | 1101 | 0 1102 | ENDBLK 1103 | 5 1104 | 21 1105 | 100 1106 | AcDbEntity 1107 | 8 1108 | 0 1109 | 100 1110 | AcDbBlockEnd 1111 | 0 1112 | BLOCK 1113 | 5 1114 | 1C 1115 | 100 1116 | AcDbEntity 1117 | 8 1118 | 0 1119 | 100 1120 | AcDbBlockBegin 1121 | 2 1122 | *Paper_Space 1123 | 70 1124 | 0 1125 | 10 1126 | 0.0 1127 | 20 1128 | 0.0 1129 | 30 1130 | 0.0 1131 | 3 1132 | *Paper_Space 1133 | 1 1134 | 1135 | 0 1136 | ENDBLK 1137 | 5 1138 | 1D 1139 | 100 1140 | AcDbEntity 1141 | 8 1142 | 0 1143 | 100 1144 | AcDbBlockEnd 1145 | 0 1146 | ENDSEC 1147 | 0 1148 | SECTION 1149 | 2 1150 | ENTITIES 1151 | 0 1152 | LINE 1153 | 5 1154 | 20A 1155 | 100 1156 | AcDbEntity 1157 | 8 1158 | 0 1159 | 100 1160 | AcDbLine 1161 | 62 1162 | 7 1163 | 6 1164 | CONTINUOUS 1165 | 10 1166 | 0.0 1167 | 20 1168 | 0.0 1169 | 11 1170 | 0.0 1171 | 21 1172 | 210.0 1173 | 0 1174 | LINE 1175 | 5 1176 | 20B 1177 | 100 1178 | AcDbEntity 1179 | 8 1180 | 0 1181 | 100 1182 | AcDbLine 1183 | 62 1184 | 7 1185 | 6 1186 | CONTINUOUS 1187 | 10 1188 | 0.0 1189 | 20 1190 | 0.0 1191 | 11 1192 | 297.0 1193 | 21 1194 | 0.0 1195 | 0 1196 | LINE 1197 | 5 1198 | 20C 1199 | 100 1200 | AcDbEntity 1201 | 8 1202 | 0 1203 | 100 1204 | AcDbLine 1205 | 62 1206 | 7 1207 | 6 1208 | CONTINUOUS 1209 | 10 1210 | 0.0 1211 | 20 1212 | 210.0 1213 | 11 1214 | 297.0 1215 | 21 1216 | 210.0 1217 | 0 1218 | LINE 1219 | 5 1220 | 20D 1221 | 100 1222 | AcDbEntity 1223 | 8 1224 | 0 1225 | 100 1226 | AcDbLine 1227 | 62 1228 | 7 1229 | 6 1230 | CONTINUOUS 1231 | 10 1232 | 297.0 1233 | 20 1234 | 0.0 1235 | 11 1236 | 297.0 1237 | 21 1238 | 210.0 1239 | 0 1240 | LINE 1241 | 5 1242 | 20E 1243 | 100 1244 | AcDbEntity 1245 | 8 1246 | 0 1247 | 100 1248 | AcDbLine 1249 | 62 1250 | 7 1251 | 6 1252 | CONTINUOUS 1253 | 10 1254 | 146.8278808594 1255 | 20 1256 | 144.6669275562 1257 | 11 1258 | 146.8278808594 1259 | 21 1260 | 126.6682514459 1261 | 0 1262 | LINE 1263 | 5 1264 | 20F 1265 | 100 1266 | AcDbEntity 1267 | 8 1268 | 0 1269 | 100 1270 | AcDbLine 1271 | 62 1272 | 7 1273 | 6 1274 | CONTINUOUS 1275 | 10 1276 | 138.978375921 1277 | 20 1278 | 113.0725100784 1279 | 11 1280 | 123.3910651751 1281 | 21 1282 | 104.0731720233 1283 | 0 1284 | LINE 1285 | 5 1286 | 210 1287 | 100 1288 | AcDbEntity 1289 | 8 1290 | 0 1291 | 100 1292 | AcDbLine 1293 | 62 1294 | 7 1295 | 6 1296 | CONTINUOUS 1297 | 10 1298 | 159.1773857977 1299 | 20 1300 | 105.2782814444 1301 | 11 1302 | 174.7646965437 1303 | 21 1304 | 96.2789433893 1305 | 0 1306 | LINE 1307 | 5 1308 | 211 1309 | 100 1310 | AcDbEntity 1311 | 8 1312 | 0 1313 | 100 1314 | AcDbLine 1315 | 62 1316 | 7 1317 | 6 1318 | CONTINUOUS 1319 | 10 1320 | 155.8278808594 1321 | 20 1322 | 126.6682514459 1323 | 11 1324 | 155.8278808594 1325 | 21 1326 | 144.6669275562 1327 | 0 1328 | LINE 1329 | 5 1330 | 212 1331 | 100 1332 | AcDbEntity 1333 | 8 1334 | 0 1335 | 100 1336 | AcDbLine 1337 | 62 1338 | 7 1339 | 6 1340 | CONTINUOUS 1341 | 10 1342 | 127.8910651751 1343 | 20 1344 | 96.2789433893 1345 | 11 1346 | 143.478375921 1347 | 21 1348 | 105.2782814444 1349 | 0 1350 | LINE 1351 | 5 1352 | 213 1353 | 100 1354 | AcDbEntity 1355 | 8 1356 | 0 1357 | 100 1358 | AcDbLine 1359 | 62 1360 | 7 1361 | 6 1362 | CONTINUOUS 1363 | 10 1364 | 179.2646965437 1365 | 20 1366 | 104.0731720233 1367 | 11 1368 | 163.6773857977 1369 | 21 1370 | 113.0725100784 1371 | 0 1372 | CIRCLE 1373 | 5 1374 | 214 1375 | 100 1376 | AcDbEntity 1377 | 8 1378 | 02___PRT_ALL_AXES 1379 | 100 1380 | AcDbCircle 1381 | 62 1382 | 7 1383 | 6 1384 | CONTINUOUS 1385 | 10 1386 | 151.3278808594 1387 | 20 1388 | 115.0063476563 1389 | 40 1390 | 40.0 1391 | 0 1392 | ARC 1393 | 5 1394 | 215 1395 | 100 1396 | AcDbEntity 1397 | 8 1398 | 0 1399 | 100 1400 | AcDbCircle 1401 | 62 1402 | 7 1403 | 6 1404 | CONTINUOUS 1405 | 10 1406 | 151.3278808594 1407 | 20 1408 | 115.0063476563 1409 | 40 1410 | 30.0 1411 | 100 1412 | AcDbArc 1413 | 50 1414 | 218.6269265587 1415 | 51 1416 | 321.3730734413 1417 | 0 1418 | ARC 1419 | 5 1420 | 216 1421 | 100 1422 | AcDbEntity 1423 | 8 1424 | 0 1425 | 100 1426 | AcDbCircle 1427 | 62 1428 | 7 1429 | 6 1430 | CONTINUOUS 1431 | 10 1432 | 151.3278808594 1433 | 20 1434 | 115.0063476563 1435 | 40 1436 | 30.0 1437 | 100 1438 | AcDbArc 1439 | 50 1440 | 98.6269265587 1441 | 51 1442 | 201.3730734413 1443 | 0 1444 | ARC 1445 | 5 1446 | 217 1447 | 100 1448 | AcDbEntity 1449 | 8 1450 | 0 1451 | 100 1452 | AcDbCircle 1453 | 62 1454 | 7 1455 | 6 1456 | CONTINUOUS 1457 | 10 1458 | 151.3278808594 1459 | 20 1460 | 115.0063476563 1461 | 40 1462 | 30.0 1463 | 100 1464 | AcDbArc 1465 | 50 1466 | 338.6269265587 1467 | 51 1468 | 81.3730734413 1469 | 0 1470 | ARC 1471 | 5 1472 | 218 1473 | 100 1474 | AcDbEntity 1475 | 8 1476 | 0 1477 | 100 1478 | AcDbCircle 1479 | 62 1480 | 7 1481 | 6 1482 | CONTINUOUS 1483 | 10 1484 | 151.3278808594 1485 | 20 1486 | 115.0063476563 1487 | 40 1488 | 12.5 1489 | 100 1490 | AcDbArc 1491 | 50 1492 | 111.1001960241 1493 | 51 1494 | 188.8998039759 1495 | 0 1496 | ARC 1497 | 5 1498 | 219 1499 | 100 1500 | AcDbEntity 1501 | 8 1502 | 0 1503 | 100 1504 | AcDbCircle 1505 | 62 1506 | 7 1507 | 6 1508 | CONTINUOUS 1509 | 10 1510 | 151.3278808594 1511 | 20 1512 | 115.0063476563 1513 | 40 1514 | 12.5 1515 | 100 1516 | AcDbArc 1517 | 50 1518 | 231.1001960241 1519 | 51 1520 | 308.8998039759 1521 | 0 1522 | ARC 1523 | 5 1524 | 21A 1525 | 100 1526 | AcDbEntity 1527 | 8 1528 | 0 1529 | 100 1530 | AcDbCircle 1531 | 62 1532 | 7 1533 | 6 1534 | CONTINUOUS 1535 | 10 1536 | 151.3278808594 1537 | 20 1538 | 115.0063476563 1539 | 40 1540 | 12.5 1541 | 100 1542 | AcDbArc 1543 | 50 1544 | 351.1001960241 1545 | 51 1546 | 68.8998039759 1547 | 0 1548 | CIRCLE 1549 | 5 1550 | 21B 1551 | 100 1552 | AcDbEntity 1553 | 8 1554 | 0 1555 | 100 1556 | AcDbCircle 1557 | 62 1558 | 7 1559 | 6 1560 | CONTINUOUS 1561 | 10 1562 | 151.3278808594 1563 | 20 1564 | 115.0063476563 1565 | 40 1566 | 5.5 1567 | 0 1568 | CIRCLE 1569 | 5 1570 | 21C 1571 | 100 1572 | AcDbEntity 1573 | 8 1574 | 02___PRT_ALL_AXES 1575 | 100 1576 | AcDbCircle 1577 | 62 1578 | 7 1579 | 6 1580 | CONTINUOUS 1581 | 10 1582 | 151.3278808594 1583 | 20 1584 | 150.0063476562 1585 | 40 1586 | 3.0 1587 | 0 1588 | CIRCLE 1589 | 5 1590 | 21D 1591 | 100 1592 | AcDbEntity 1593 | 8 1594 | 02___PRT_ALL_AXES 1595 | 100 1596 | AcDbCircle 1597 | 62 1598 | 7 1599 | 6 1600 | CONTINUOUS 1601 | 10 1602 | 171.9003646896 1603 | 20 1604 | 143.3219424594 1605 | 40 1606 | 3.0 1607 | 0 1608 | CIRCLE 1609 | 5 1610 | 21E 1611 | 100 1612 | AcDbEntity 1613 | 8 1614 | 02___PRT_ALL_AXES 1615 | 100 1616 | AcDbCircle 1617 | 62 1618 | 7 1619 | 6 1620 | CONTINUOUS 1621 | 10 1622 | 184.6148589297 1623 | 20 1624 | 125.8219424594 1625 | 40 1626 | 3.0 1627 | 0 1628 | CIRCLE 1629 | 5 1630 | 21F 1631 | 100 1632 | AcDbEntity 1633 | 8 1634 | 02___PRT_ALL_AXES 1635 | 100 1636 | AcDbCircle 1637 | 62 1638 | 7 1639 | 6 1640 | CONTINUOUS 1641 | 10 1642 | 184.6148589297 1643 | 20 1644 | 104.1907528531 1645 | 40 1646 | 3.0 1647 | 0 1648 | CIRCLE 1649 | 5 1650 | 220 1651 | 100 1652 | AcDbEntity 1653 | 8 1654 | 02___PRT_ALL_AXES 1655 | 100 1656 | AcDbCircle 1657 | 62 1658 | 7 1659 | 6 1660 | CONTINUOUS 1661 | 10 1662 | 171.9003646896 1663 | 20 1664 | 86.6907528531 1665 | 40 1666 | 3.0 1667 | 0 1668 | CIRCLE 1669 | 5 1670 | 221 1671 | 100 1672 | AcDbEntity 1673 | 8 1674 | 02___PRT_ALL_AXES 1675 | 100 1676 | AcDbCircle 1677 | 62 1678 | 7 1679 | 6 1680 | CONTINUOUS 1681 | 10 1682 | 151.3278808594 1683 | 20 1684 | 80.0063476563 1685 | 40 1686 | 3.0 1687 | 0 1688 | CIRCLE 1689 | 5 1690 | 222 1691 | 100 1692 | AcDbEntity 1693 | 8 1694 | 02___PRT_ALL_AXES 1695 | 100 1696 | AcDbCircle 1697 | 62 1698 | 7 1699 | 6 1700 | CONTINUOUS 1701 | 10 1702 | 130.7553970291 1703 | 20 1704 | 86.6907528531 1705 | 40 1706 | 3.0 1707 | 0 1708 | CIRCLE 1709 | 5 1710 | 223 1711 | 100 1712 | AcDbEntity 1713 | 8 1714 | 02___PRT_ALL_AXES 1715 | 100 1716 | AcDbCircle 1717 | 62 1718 | 7 1719 | 6 1720 | CONTINUOUS 1721 | 10 1722 | 118.040902789 1723 | 20 1724 | 104.1907528531 1725 | 40 1726 | 3.0 1727 | 0 1728 | CIRCLE 1729 | 5 1730 | 224 1731 | 100 1732 | AcDbEntity 1733 | 8 1734 | 02___PRT_ALL_AXES 1735 | 100 1736 | AcDbCircle 1737 | 62 1738 | 7 1739 | 6 1740 | CONTINUOUS 1741 | 10 1742 | 118.040902789 1743 | 20 1744 | 125.8219424594 1745 | 40 1746 | 3.0 1747 | 0 1748 | CIRCLE 1749 | 5 1750 | 225 1751 | 100 1752 | AcDbEntity 1753 | 8 1754 | 02___PRT_ALL_AXES 1755 | 100 1756 | AcDbCircle 1757 | 62 1758 | 7 1759 | 6 1760 | CONTINUOUS 1761 | 10 1762 | 130.7553970291 1763 | 20 1764 | 143.3219424594 1765 | 40 1766 | 3.0 1767 | 0 1768 | CIRCLE 1769 | 5 1770 | 226 1771 | 100 1772 | AcDbEntity 1773 | 8 1774 | 02___PRT_ALL_AXES 1775 | 100 1776 | AcDbCircle 1777 | 62 1778 | 7 1779 | 6 1780 | CONTINUOUS 1781 | 10 1782 | 151.3278808594 1783 | 20 1784 | 107.0063476563 1785 | 40 1786 | 1.25 1787 | 0 1788 | CIRCLE 1789 | 5 1790 | 227 1791 | 100 1792 | AcDbEntity 1793 | 8 1794 | 02___PRT_ALL_AXES 1795 | 100 1796 | AcDbCircle 1797 | 62 1798 | 7 1799 | 6 1800 | CONTINUOUS 1801 | 10 1802 | 143.3278808594 1803 | 20 1804 | 115.0063476563 1805 | 40 1806 | 1.25 1807 | 0 1808 | CIRCLE 1809 | 5 1810 | 228 1811 | 100 1812 | AcDbEntity 1813 | 8 1814 | 02___PRT_ALL_AXES 1815 | 100 1816 | AcDbCircle 1817 | 62 1818 | 7 1819 | 6 1820 | CONTINUOUS 1821 | 10 1822 | 151.3278808594 1823 | 20 1824 | 123.0063476563 1825 | 40 1826 | 1.25 1827 | 0 1828 | CIRCLE 1829 | 5 1830 | 229 1831 | 100 1832 | AcDbEntity 1833 | 8 1834 | 02___PRT_ALL_AXES 1835 | 100 1836 | AcDbCircle 1837 | 62 1838 | 7 1839 | 6 1840 | CONTINUOUS 1841 | 10 1842 | 159.3278808594 1843 | 20 1844 | 115.0063476563 1845 | 40 1846 | 1.25 1847 | 0 1848 | ENDSEC 1849 | 0 1850 | SECTION 1851 | 2 1852 | OBJECTS 1853 | 0 1854 | DICTIONARY 1855 | 5 1856 | C 1857 | 100 1858 | AcDbDictionary 1859 | 280 1860 | 0 1861 | 281 1862 | 1 1863 | 3 1864 | ACAD_GROUP 1865 | 350 1866 | D 1867 | 3 1868 | ACAD_MLINESTYLE 1869 | 350 1870 | 17 1871 | 3 1872 | ACAD_LAYOUT 1873 | 350 1874 | 1A 1875 | 3 1876 | ACAD_PLOTSETTINGS 1877 | 350 1878 | 19 1879 | 3 1880 | ACAD_PLOTSTYLENAME 1881 | 350 1882 | E 1883 | 0 1884 | DICTIONARY 1885 | 5 1886 | D 1887 | 102 1888 | {ACAD_REACTORS 1889 | 330 1890 | C 1891 | 102 1892 | } 1893 | 100 1894 | AcDbDictionary 1895 | 280 1896 | 0 1897 | 281 1898 | 1 1899 | 0 1900 | ACDBDICTIONARYWDFLT 1901 | 5 1902 | E 1903 | 102 1904 | {ACAD_REACTORS 1905 | 330 1906 | C 1907 | 102 1908 | } 1909 | 100 1910 | AcDbDictionary 1911 | 281 1912 | 1 1913 | 3 1914 | Normal 1915 | 350 1916 | F 1917 | 100 1918 | AcDbDictionaryWithDefault 1919 | 340 1920 | F 1921 | 0 1922 | DICTIONARY 1923 | 5 1924 | 17 1925 | 102 1926 | {ACAD_REACTORS 1927 | 330 1928 | C 1929 | 102 1930 | } 1931 | 100 1932 | AcDbDictionary 1933 | 280 1934 | 0 1935 | 281 1936 | 1 1937 | 3 1938 | Standard 1939 | 350 1940 | 18 1941 | 0 1942 | DICTIONARY 1943 | 5 1944 | 19 1945 | 102 1946 | {ACAD_REACTORS 1947 | 330 1948 | C 1949 | 102 1950 | } 1951 | 100 1952 | AcDbDictionary 1953 | 281 1954 | 1 1955 | 0 1956 | DICTIONARY 1957 | 5 1958 | 1A 1959 | 102 1960 | {ACAD_REACTORS 1961 | 330 1962 | C 1963 | 102 1964 | } 1965 | 100 1966 | AcDbDictionary 1967 | 281 1968 | 1 1969 | 3 1970 | Model 1971 | 350 1972 | 22A 1973 | 3 1974 | Layout1 1975 | 350 1976 | 22B 1977 | 0 1978 | ACDBPLACEHOLDER 1979 | 5 1980 | F 1981 | 102 1982 | {ACAD_REACTORS 1983 | 330 1984 | E 1985 | 102 1986 | } 1987 | 0 1988 | MLINESTYLE 1989 | 5 1990 | 18 1991 | 102 1992 | {ACAD_REACTORS 1993 | 330 1994 | 17 1995 | 102 1996 | } 1997 | 100 1998 | AcDbMlineStyle 1999 | 2 2000 | STANDARD 2001 | 70 2002 | 0 2003 | 3 2004 | 2005 | 62 2006 | 256 2007 | 51 2008 | 90.0 2009 | 52 2010 | 90.0 2011 | 71 2012 | 2 2013 | 49 2014 | 0.5 2015 | 62 2016 | 256 2017 | 6 2018 | BYLAYER 2019 | 49 2020 | -0.5 2021 | 62 2022 | 256 2023 | 6 2024 | BYLAYER 2025 | 0 2026 | LAYOUT 2027 | 5 2028 | 22A 2029 | 102 2030 | {ACAD_REACTORS 2031 | 330 2032 | 1A 2033 | 102 2034 | } 2035 | 100 2036 | AcDbPlotSettings 2037 | 1 2038 | 2039 | 2 2040 | none_device 2041 | 4 2042 | ISO_A4_(297.00_x_210.00_MM) 2043 | 6 2044 | 2045 | 40 2046 | 0.0 2047 | 41 2048 | 0.0 2049 | 42 2050 | 0.0 2051 | 43 2052 | 0.0 2053 | 44 2054 | 297.0 2055 | 45 2056 | 210.0 2057 | 46 2058 | 0.0 2059 | 47 2060 | 0.0 2061 | 48 2062 | 0.0 2063 | 49 2064 | 0.0 2065 | 140 2066 | 0.0 2067 | 141 2068 | 0.0 2069 | 142 2070 | 1.0 2071 | 143 2072 | 1.0 2073 | 70 2074 | 1024 2075 | 72 2076 | 1 2077 | 73 2078 | 0 2079 | 74 2080 | 0 2081 | 7 2082 | 2083 | 75 2084 | 0 2085 | 147 2086 | 1.0 2087 | 148 2088 | 0.0 2089 | 149 2090 | 0.0 2091 | 100 2092 | AcDbLayout 2093 | 1 2094 | Model 2095 | 70 2096 | 0 2097 | 71 2098 | 0 2099 | 10 2100 | 0.0 2101 | 20 2102 | 0.0 2103 | 11 2104 | 297.0 2105 | 21 2106 | 210.0 2107 | 12 2108 | 0.0 2109 | 22 2110 | 0.0 2111 | 32 2112 | 0.0 2113 | 14 2114 | 0.0 2115 | 24 2116 | 0.0 2117 | 34 2118 | 0.0 2119 | 15 2120 | 0.0 2121 | 25 2122 | 0.0 2123 | 35 2124 | 0.0 2125 | 146 2126 | 0.0 2127 | 13 2128 | 0.0 2129 | 23 2130 | 0.0 2131 | 33 2132 | 0.0 2133 | 16 2134 | 1.0 2135 | 26 2136 | 0.0 2137 | 36 2138 | 0.0 2139 | 17 2140 | 0.0 2141 | 27 2142 | 1.0 2143 | 37 2144 | 0.0 2145 | 76 2146 | 0 2147 | 330 2148 | 207 2149 | 345 2150 | 0 2151 | 346 2152 | 0 2153 | 0 2154 | LAYOUT 2155 | 5 2156 | 22B 2157 | 102 2158 | {ACAD_REACTORS 2159 | 330 2160 | 1A 2161 | 102 2162 | } 2163 | 100 2164 | AcDbPlotSettings 2165 | 1 2166 | 2167 | 2 2168 | none_device 2169 | 4 2170 | ISO_A4_(297.00_x_210.00_MM) 2171 | 6 2172 | 2173 | 40 2174 | 0.0 2175 | 41 2176 | 0.0 2177 | 42 2178 | 0.0 2179 | 43 2180 | 0.0 2181 | 44 2182 | 297.0 2183 | 45 2184 | 210.0 2185 | 46 2186 | 0.0 2187 | 47 2188 | 0.0 2189 | 48 2190 | 0.0 2191 | 49 2192 | 0.0 2193 | 140 2194 | 0.0 2195 | 141 2196 | 0.0 2197 | 142 2198 | 1.0 2199 | 143 2200 | 1.0 2201 | 70 2202 | 0 2203 | 72 2204 | 1 2205 | 73 2206 | 0 2207 | 74 2208 | 0 2209 | 7 2210 | 2211 | 75 2212 | 0 2213 | 147 2214 | 1.0 2215 | 148 2216 | 0.0 2217 | 149 2218 | 0.0 2219 | 100 2220 | AcDbLayout 2221 | 1 2222 | Layout1 2223 | 70 2224 | 0 2225 | 71 2226 | 1 2227 | 10 2228 | 0.0 2229 | 20 2230 | 0.0 2231 | 11 2232 | 297.0 2233 | 21 2234 | 210.0 2235 | 12 2236 | 0.0 2237 | 22 2238 | 0.0 2239 | 32 2240 | 0.0 2241 | 14 2242 | 0.0 2243 | 24 2244 | 0.0 2245 | 34 2246 | 0.0 2247 | 15 2248 | 0.0 2249 | 25 2250 | 0.0 2251 | 35 2252 | 0.0 2253 | 146 2254 | 0.0 2255 | 13 2256 | 0.0 2257 | 23 2258 | 0.0 2259 | 33 2260 | 0.0 2261 | 16 2262 | 1.0 2263 | 26 2264 | 0.0 2265 | 36 2266 | 0.0 2267 | 17 2268 | 0.0 2269 | 27 2270 | 1.0 2271 | 37 2272 | 0.0 2273 | 76 2274 | 0 2275 | 330 2276 | 208 2277 | 345 2278 | 0 2279 | 346 2280 | 0 2281 | 0 2282 | ENDSEC 2283 | 0 2284 | EOF 2285 | -------------------------------------------------------------------------------- /机械结构/木材版/triangle_bar_4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/机械结构/木材版/triangle_bar_4.stl -------------------------------------------------------------------------------- /调试上位机.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/ToanTech/Lailuo_DengFOC/97c59239323134dcb18f4683f07473cb779ef399/调试上位机.zip --------------------------------------------------------------------------------