├── Arduino Sketch └── sketch_Annin_Robot │ └── sketch_Annin_Robot.ino ├── Assembly Instructions.pdf ├── Bill Of Materials.pdf ├── LICENSE.MD ├── README.md ├── STL files ├── Arduino Mount.STL ├── Collar 1 inch.STL ├── Gear J5 ring carrier cap.STL ├── Gear J5 ring carrier.STL ├── Gear J5 worm bushing.STL ├── Gripper Cover side plate.STL ├── Gripper Motor side plate.STL ├── Gripper center spur.STL ├── Gripper left jaw.STL ├── Gripper right jaw.STL ├── Home cradle.STL ├── J1 Alignment Ring.STL ├── J1 Base.STL ├── J1 Turret cover.STL ├── J1 Turret.STL ├── J2 Arm Cover.STL ├── J2 Arm Left.STL ├── J2 Arm Right.STL ├── J2 Drive Block.STL ├── J2 Drive Rod Support Block.STL ├── J2 Motor Support.STL ├── J2 Spacer 2.STL ├── J2 Spacer.STL ├── J2 nut cap.STL ├── J3 Spindle.STL ├── J3 Turret cap.STL ├── J3 Turret.STL ├── J4 Boom left.STL ├── J4 Boom right.STL ├── J4 Boom.STL ├── J4 Collar 1 inch.STL ├── J4 wire holder.STL ├── J5 Clevis Center.STL ├── J5 Clevis Left Arm.STL ├── J5 Clevis Right Arm.STL ├── J5 Clevis.STL ├── J5 Motor Mount.STL ├── J5 Turret Center.STL ├── J5 Turret Left Arm.STL ├── J5 Turret Right Arm.STL ├── J5 Turret.STL ├── Mouse Holder.STL ├── coupler.STL ├── timing belt coupler.STL └── ~$J2 Arm Cover.SLDPRT ├── Software Executable └── Annin_Robot_EXE.zip ├── Software Source Code ├── ARbot.cal ├── ARbot.ico ├── Annin Robot.py ├── new ├── play-icon.gif ├── setup.py └── stop-icon.gif └── Step files └── Step files.zip /Arduino Sketch/sketch_Annin_Robot/sketch_Annin_Robot.ino: -------------------------------------------------------------------------------- 1 | /* Annin Robot - Stepper motor robot control software 2 | Copyright (C) 2016 Chris Annin 3 | 4 | This program is free software: you can redistribute it and/or modify 5 | it under the terms of the GNU General Public License as published by 6 | the Free Software Foundation, either version 3 of the License, or 7 | any later version. 8 | 9 | This program is distributed in the hope that it will be useful, 10 | but WITHOUT ANY WARRANTY; without even the implied warranty of 11 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 12 | GNU General Public License for more details. 13 | 14 | You should have received a copy of the GNU General Public License 15 | along with this program. If not, see . 16 | 17 | chris.annin@gmail.com 18 | */ 19 | 20 | #include 21 | 22 | Servo servo0; 23 | Servo servo1; 24 | Servo servo2; 25 | Servo servo3; 26 | Servo servo4; 27 | Servo servo5; 28 | Servo servo6; 29 | Servo servo7; 30 | 31 | String inData; 32 | String function; 33 | 34 | const int J1stepPin = 2; 35 | const int J1dirPin = 3; 36 | const int J2stepPin = 4; 37 | const int J2dirPin = 5; 38 | const int J3stepPin = 6; 39 | const int J3dirPin = 7; 40 | const int J4stepPin = 8; 41 | const int J4dirPin = 9; 42 | const int J5stepPin = 10; 43 | const int J5dirPin = 11; 44 | const int J6stepPin = 12; 45 | const int J6dirPin = 13; 46 | 47 | const int Input22 = 22; 48 | const int Input23 = 23; 49 | const int Input24 = 24; 50 | const int Input25 = 25; 51 | const int Input26 = 26; 52 | const int Input27 = 27; 53 | const int Input28 = 28; 54 | const int Input29 = 29; 55 | const int Input30 = 30; 56 | const int Input31 = 31; 57 | const int Input32 = 32; 58 | const int Input33 = 33; 59 | const int Input34 = 34; 60 | const int Input35 = 35; 61 | const int Input36 = 36; 62 | const int Input37 = 37; 63 | 64 | const int Output38 = 38; 65 | const int Output39 = 39; 66 | const int Output40 = 40; 67 | const int Output41 = 41; 68 | const int Output42 = 42; 69 | const int Output43 = 43; 70 | const int Output44 = 44; 71 | const int Output45 = 45; 72 | const int Output46 = 46; 73 | const int Output47 = 47; 74 | const int Output48 = 48; 75 | const int Output49 = 49; 76 | const int Output50 = 50; 77 | const int Output51 = 51; 78 | const int Output52 = 52; 79 | const int Output53 = 53; 80 | 81 | 82 | void setup() { 83 | // put your setup code here, to run once: 84 | Serial.begin(9600); 85 | 86 | pinMode(A0, OUTPUT); 87 | pinMode(A1, OUTPUT); 88 | pinMode(A2, OUTPUT); 89 | pinMode(A3, OUTPUT); 90 | pinMode(A4, OUTPUT); 91 | pinMode(A5, OUTPUT); 92 | pinMode(A6, OUTPUT); 93 | pinMode(A7, OUTPUT); 94 | 95 | pinMode(J1stepPin, OUTPUT); 96 | pinMode(J1dirPin, OUTPUT); 97 | pinMode(J2stepPin, OUTPUT); 98 | pinMode(J2dirPin, OUTPUT); 99 | pinMode(J3stepPin, OUTPUT); 100 | pinMode(J3dirPin, OUTPUT); 101 | pinMode(J4stepPin, OUTPUT); 102 | pinMode(J4dirPin, OUTPUT); 103 | pinMode(J5stepPin, OUTPUT); 104 | pinMode(J5dirPin, OUTPUT); 105 | pinMode(J6stepPin, OUTPUT); 106 | pinMode(J6dirPin, OUTPUT); 107 | 108 | pinMode(Input22, INPUT); 109 | pinMode(Input23, INPUT); 110 | pinMode(Input24, INPUT); 111 | pinMode(Input25, INPUT); 112 | pinMode(Input26, INPUT); 113 | pinMode(Input27, INPUT); 114 | pinMode(Input28, INPUT); 115 | pinMode(Input29, INPUT); 116 | pinMode(Input30, INPUT); 117 | pinMode(Input31, INPUT); 118 | pinMode(Input32, INPUT); 119 | pinMode(Input33, INPUT); 120 | pinMode(Input34, INPUT); 121 | pinMode(Input35, INPUT); 122 | pinMode(Input36, INPUT); 123 | pinMode(Input37, INPUT); 124 | 125 | pinMode(Output38, OUTPUT); 126 | pinMode(Output39, OUTPUT); 127 | pinMode(Output40, OUTPUT); 128 | pinMode(Output41, OUTPUT); 129 | pinMode(Output42, OUTPUT); 130 | pinMode(Output43, OUTPUT); 131 | pinMode(Output44, OUTPUT); 132 | pinMode(Output45, OUTPUT); 133 | pinMode(Output46, OUTPUT); 134 | pinMode(Output47, OUTPUT); 135 | pinMode(Output48, OUTPUT); 136 | pinMode(Output49, OUTPUT); 137 | pinMode(Output50, OUTPUT); 138 | pinMode(Output51, OUTPUT); 139 | pinMode(Output52, OUTPUT); 140 | pinMode(Output53, OUTPUT); 141 | 142 | servo0.attach(A0); 143 | servo1.attach(A1); 144 | servo2.attach(A2); 145 | servo3.attach(A3); 146 | servo4.attach(A4); 147 | servo5.attach(A5); 148 | servo6.attach(A6); 149 | servo7.attach(A7); 150 | 151 | digitalWrite(Output38, HIGH); 152 | digitalWrite(Output39, HIGH); 153 | digitalWrite(Output40, HIGH); 154 | digitalWrite(Output41, HIGH); 155 | digitalWrite(Output42, HIGH); 156 | digitalWrite(Output43, HIGH); 157 | digitalWrite(Output44, HIGH); 158 | digitalWrite(Output45, HIGH); 159 | 160 | } 161 | 162 | 163 | void loop() { 164 | while (Serial.available() > 0) 165 | { 166 | char recieved = Serial.read(); 167 | inData += recieved; 168 | // Process message when new line character is recieved 169 | if (recieved == '\n') 170 | { 171 | String function = inData.substring(0, 2); 172 | 173 | 174 | //-----COMMAND TO MOVE SERVO--------------------------------------------------- 175 | //----------------------------------------------------------------------- 176 | if (function == "SV") 177 | { 178 | int SVstart = inData.indexOf('V'); 179 | int POSstart = inData.indexOf('P'); 180 | int servoNum = inData.substring(SVstart + 1, POSstart).toInt(); 181 | int servoPOS = inData.substring(POSstart + 1).toInt(); 182 | if (servoNum == 0) 183 | { 184 | servo0.write(servoPOS); 185 | } 186 | if (servoNum == 1) 187 | { 188 | servo1.write(servoPOS); 189 | } 190 | if (servoNum == 2) 191 | { 192 | servo2.write(servoPOS); 193 | } 194 | if (servoNum == 3) 195 | { 196 | servo3.write(servoPOS); 197 | } 198 | if (servoNum == 4) 199 | { 200 | servo4.write(servoPOS); 201 | } 202 | if (servoNum == 5) 203 | { 204 | servo5.write(servoPOS); 205 | } 206 | if (servoNum == 6) 207 | { 208 | servo6.write(servoPOS); 209 | } 210 | if (servoNum == 7) 211 | { 212 | servo7.write(servoPOS); 213 | } 214 | Serial.print("Servo Done"); 215 | } 216 | 217 | 218 | 219 | 220 | //-----COMMAND TO WAIT TIME--------------------------------------------------- 221 | //----------------------------------------------------------------------- 222 | if (function == "WT") 223 | { 224 | int WTstart = inData.indexOf('S'); 225 | float WaitTime = inData.substring(WTstart + 1).toFloat(); 226 | int WaitTimeMS = WaitTime * 1000; 227 | delay(WaitTimeMS); 228 | Serial.print("Done"); 229 | } 230 | 231 | //-----COMMAND IF INPUT THEN JUMP--------------------------------------------------- 232 | //----------------------------------------------------------------------- 233 | if (function == "IJ") 234 | { 235 | int IJstart = inData.indexOf('X'); 236 | int IJTabstart = inData.indexOf('T'); 237 | int IJInputNum = inData.substring(IJstart + 1, IJTabstart).toInt(); 238 | if (digitalRead(IJInputNum) == HIGH) 239 | { 240 | Serial.println("True\n"); 241 | } 242 | if (digitalRead(IJInputNum) == LOW) 243 | { 244 | Serial.println("False\n"); 245 | } 246 | } 247 | //-----COMMAND SET OUTPUT ON--------------------------------------------------- 248 | //----------------------------------------------------------------------- 249 | if (function == "ON") 250 | { 251 | int ONstart = inData.indexOf('X'); 252 | int outputNum = inData.substring(ONstart + 1).toInt(); 253 | digitalWrite(outputNum, HIGH); 254 | Serial.print("Done"); 255 | } 256 | //-----COMMAND SET OUTPUT OFF--------------------------------------------------- 257 | //----------------------------------------------------------------------- 258 | if (function == "OF") 259 | { 260 | int ONstart = inData.indexOf('X'); 261 | int outputNum = inData.substring(ONstart + 1).toInt(); 262 | digitalWrite(outputNum, LOW); 263 | Serial.print("Done"); 264 | } 265 | //-----COMMAND TO WAIT INPUT ON--------------------------------------------------- 266 | //----------------------------------------------------------------------- 267 | if (function == "WI") 268 | { 269 | int WIstart = inData.indexOf('N'); 270 | int InputNum = inData.substring(WIstart + 1).toInt(); 271 | while (digitalRead(InputNum) == LOW) { 272 | delay(100); 273 | } 274 | Serial.print("Done"); 275 | } 276 | //-----COMMAND TO WAIT INPUT OFF--------------------------------------------------- 277 | //----------------------------------------------------------------------- 278 | if (function == "WO") 279 | { 280 | int WIstart = inData.indexOf('N'); 281 | int InputNum = inData.substring(WIstart + 1).toInt(); 282 | 283 | //String InputStr = String("Input" + InputNum); 284 | //uint8_t Input = atoi(InputStr.c_str ()); 285 | while (digitalRead(InputNum) == HIGH) { 286 | delay(100); 287 | } 288 | Serial.print("Done"); 289 | } 290 | //-----COMMAND TO MOVE--------------------------------------------------- 291 | //----------------------------------------------------------------------- 292 | if (function == "MJ") 293 | { 294 | int J1start = inData.indexOf('A'); 295 | int J2start = inData.indexOf('B'); 296 | int J3start = inData.indexOf('C'); 297 | int J4start = inData.indexOf('D'); 298 | int J5start = inData.indexOf('E'); 299 | int J6start = inData.indexOf('F'); 300 | int SPstart = inData.indexOf('S'); 301 | int J1dir = inData.substring(J1start + 1, J1start + 2).toInt(); 302 | int J2dir = inData.substring(J2start + 1, J2start + 2).toInt(); 303 | int J3dir = inData.substring(J3start + 1, J3start + 2).toInt(); 304 | int J4dir = inData.substring(J4start + 1, J4start + 2).toInt(); 305 | int J5dir = inData.substring(J5start + 1, J5start + 2).toInt(); 306 | int J6dir = inData.substring(J6start + 1, J6start + 2).toInt(); 307 | int J1step = inData.substring(J1start + 2, J2start).toInt(); 308 | int J2step = inData.substring(J2start + 2, J3start).toInt(); 309 | int J3step = inData.substring(J3start + 2, J4start).toInt(); 310 | int J4step = inData.substring(J4start + 2, J5start).toInt(); 311 | int J5step = inData.substring(J5start + 2, J6start).toInt(); 312 | int J6step = inData.substring(J6start + 2, SPstart).toInt(); 313 | float SpeedIn = inData.substring(SPstart + 1).toFloat(); 314 | SpeedIn = (SpeedIn / 100); 315 | float CalcSpeed = (1600 / SpeedIn); 316 | int Speed = int(CalcSpeed); 317 | 318 | //FIND HIGHEST STEP 319 | int highStep = J1step; 320 | if (J2step > highStep) 321 | { 322 | highStep = J2step; 323 | } 324 | if (J3step > highStep) 325 | { 326 | highStep = J3step; 327 | } 328 | if (J4step > highStep) 329 | { 330 | highStep = J4step; 331 | } 332 | if (J5step > highStep) 333 | { 334 | highStep = J5step; 335 | } 336 | if (J6step > highStep) 337 | { 338 | highStep = J6step; 339 | } 340 | 341 | 342 | 343 | //DETERMINE AXIS SKIP INCREMENT 344 | int J1skip = (highStep / J1step); 345 | int J2skip = (highStep / J2step); 346 | int J3skip = (highStep / J3step); 347 | int J4skip = (highStep / J4step); 348 | int J5skip = (highStep / J5step); 349 | int J6skip = (highStep / J6step); 350 | 351 | 352 | //RESET COUNTERS 353 | int J1done = 0; 354 | int J2done = 0; 355 | int J3done = 0; 356 | int J4done = 0; 357 | int J5done = 0; 358 | int J6done = 0; 359 | 360 | //RESET SKIP CURRENT 361 | int J1skipCur = 0; 362 | int J2skipCur = 0; 363 | int J3skipCur = 0; 364 | int J4skipCur = 0; 365 | int J5skipCur = 0; 366 | int J6skipCur = 0; 367 | 368 | //SET DIRECTIONS 369 | if (J1dir == 1) 370 | { 371 | digitalWrite(J1dirPin, HIGH); 372 | } 373 | else if (J1dir == 0) 374 | { 375 | digitalWrite(J1dirPin, LOW); 376 | } 377 | if (J2dir == 1) 378 | { 379 | digitalWrite(J2dirPin, HIGH); 380 | } 381 | else if (J2dir == 0) 382 | { 383 | digitalWrite(J2dirPin, LOW); 384 | } 385 | if (J3dir == 1) 386 | { 387 | digitalWrite(J3dirPin, HIGH); 388 | } 389 | else if (J3dir == 0) 390 | { 391 | digitalWrite(J3dirPin, LOW); 392 | } 393 | if (J4dir == 1) 394 | { 395 | digitalWrite(J4dirPin, HIGH); 396 | } 397 | else if (J4dir == 0) 398 | { 399 | digitalWrite(J4dirPin, LOW); 400 | } 401 | if (J5dir == 1) 402 | { 403 | digitalWrite(J5dirPin, HIGH); 404 | } 405 | else if (J5dir == 0) 406 | { 407 | digitalWrite(J5dirPin, LOW); 408 | } 409 | if (J6dir == 1) 410 | { 411 | digitalWrite(J6dirPin, HIGH); 412 | } 413 | else if (J6dir == 0) 414 | { 415 | digitalWrite(J6dirPin, LOW); 416 | } 417 | 418 | 419 | 420 | 421 | //DRIVE MOTORS 422 | while (J1done < J1step || J2done < J2step || J3done < J3step || J4done < J4step || J5done < J5step || J6done < J6step) 423 | { 424 | if (J1done < J1step && J1skipCur == 0) 425 | { 426 | digitalWrite(J1stepPin, HIGH); 427 | } 428 | if (J2done < J2step && J2skipCur == 0) 429 | { 430 | digitalWrite(J2stepPin, HIGH); 431 | } 432 | if (J3done < J3step && J3skipCur == 0) 433 | { 434 | digitalWrite(J3stepPin, HIGH); 435 | } 436 | if (J4done < J4step && J4skipCur == 0) 437 | { 438 | digitalWrite(J4stepPin, HIGH); 439 | } 440 | if (J5done < J5step && J5skipCur == 0) 441 | { 442 | digitalWrite(J5stepPin, HIGH); 443 | } 444 | if (J6done < J6step && J6skipCur == 0) 445 | { 446 | digitalWrite(J6stepPin, HIGH); 447 | } 448 | //#############DELAY AND SET LOW 449 | delayMicroseconds(0); 450 | if (J1done < J1step && J1skipCur == 0) 451 | { 452 | digitalWrite(J1stepPin, LOW); 453 | J1done = ++J1done; 454 | } 455 | if (J2done < J2step && J2skipCur == 0) 456 | { 457 | digitalWrite(J2stepPin, LOW); 458 | J2done = ++J2done; 459 | } 460 | if (J3done < J3step && J3skipCur == 0) 461 | { 462 | digitalWrite(J3stepPin, LOW); 463 | J3done = ++J3done; 464 | } 465 | if (J4done < J4step && J4skipCur == 0) 466 | { 467 | digitalWrite(J4stepPin, LOW); 468 | J4done = ++J4done; 469 | } 470 | if (J5done < J5step && J5skipCur == 0) 471 | { 472 | digitalWrite(J5stepPin, LOW); 473 | J5done = ++J5done;; 474 | } 475 | if (J6done < J6step && J6skipCur == 0) 476 | { 477 | digitalWrite(J6stepPin, LOW); 478 | J6done = ++J6done; 479 | } 480 | //#############DELAY BEFORE RESTARTING LOOP AND SETTING HIGH AGAIN 481 | delayMicroseconds(Speed); 482 | //increment skip count 483 | J1skipCur = ++J1skipCur; 484 | J2skipCur = ++J2skipCur; 485 | J3skipCur = ++J3skipCur; 486 | J4skipCur = ++J4skipCur; 487 | J5skipCur = ++J5skipCur; 488 | J6skipCur = ++J6skipCur; 489 | //if skiped enough times set back to zero 490 | if (J1skipCur == J1skip) 491 | { 492 | J1skipCur = 0; 493 | } 494 | if (J2skipCur == J2skip) 495 | { 496 | J2skipCur = 0; 497 | } 498 | if (J3skipCur == J3skip) 499 | { 500 | J3skipCur = 0; 501 | } 502 | if (J4skipCur == J4skip) 503 | { 504 | J4skipCur = 0; 505 | } 506 | if (J5skipCur == J5skip) 507 | { 508 | J5skipCur = 0; 509 | } 510 | if (J6skipCur == J6skip) 511 | { 512 | J6skipCur = 0; 513 | } 514 | } 515 | inData = ""; // Clear recieved buffer 516 | Serial.print("Move Done"); 517 | } 518 | else 519 | { 520 | inData = ""; // Clear recieved buffer 521 | } 522 | } 523 | } 524 | } 525 | 526 | 527 | 528 | 529 | 530 | -------------------------------------------------------------------------------- /Assembly Instructions.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/Assembly Instructions.pdf -------------------------------------------------------------------------------- /Bill Of Materials.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/Bill Of Materials.pdf -------------------------------------------------------------------------------- /LICENSE.MD: -------------------------------------------------------------------------------- 1 | GNU GENERAL PUBLIC LICENSE 2 | Version 3, 29 June 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 General Public License is a free, copyleft license for 11 | software and other kinds of works. 12 | 13 | The licenses for most software and other practical works are designed 14 | to take away your freedom to share and change the works. By contrast, 15 | the GNU General Public License is intended to guarantee your freedom to 16 | share and change all versions of a program--to make sure it remains free 17 | software for all its users. We, the Free Software Foundation, use the 18 | GNU General Public License for most of our software; it applies also to 19 | any other work released this way by its authors. You can apply it to 20 | your programs, too. 21 | 22 | When we speak of free software, we are referring to freedom, not 23 | price. Our General Public Licenses are designed to make sure that you 24 | have the freedom to distribute copies of free software (and charge for 25 | them if you wish), that you receive source code or can get it if you 26 | want it, that you can change the software or use pieces of it in new 27 | free programs, and that you know you can do these things. 28 | 29 | To protect your rights, we need to prevent others from denying you 30 | these rights or asking you to surrender the rights. Therefore, you have 31 | certain responsibilities if you distribute copies of the software, or if 32 | you modify it: responsibilities to respect the freedom of others. 33 | 34 | For example, if you distribute copies of such a program, whether 35 | gratis or for a fee, you must pass on to the recipients the same 36 | freedoms that you received. You must make sure that they, too, receive 37 | or can get the source code. And you must show them these terms so they 38 | know their rights. 39 | 40 | Developers that use the GNU GPL protect your rights with two steps: 41 | (1) assert copyright on the software, and (2) offer you this License 42 | giving you legal permission to copy, distribute and/or modify it. 43 | 44 | For the developers' and authors' protection, the GPL clearly explains 45 | that there is no warranty for this free software. For both users' and 46 | authors' sake, the GPL requires that modified versions be marked as 47 | changed, so that their problems will not be attributed erroneously to 48 | authors of previous versions. 49 | 50 | Some devices are designed to deny users access to install or run 51 | modified versions of the software inside them, although the manufacturer 52 | can do so. This is fundamentally incompatible with the aim of 53 | protecting users' freedom to change the software. The systematic 54 | pattern of such abuse occurs in the area of products for individuals to 55 | use, which is precisely where it is most unacceptable. Therefore, we 56 | have designed this version of the GPL to prohibit the practice for those 57 | products. If such problems arise substantially in other domains, we 58 | stand ready to extend this provision to those domains in future versions 59 | of the GPL, as needed to protect the freedom of users. 60 | 61 | Finally, every program is threatened constantly by software patents. 62 | States should not allow patents to restrict development and use of 63 | software on general-purpose computers, but in those that do, we wish to 64 | avoid the special danger that patents applied to a free program could 65 | make it effectively proprietary. To prevent this, the GPL assures that 66 | patents cannot be used to render the program non-free. 67 | 68 | The precise terms and conditions for copying, distribution and 69 | modification follow. 70 | 71 | TERMS AND CONDITIONS 72 | 73 | 0. Definitions. 74 | 75 | "This License" refers to version 3 of the GNU General Public License. 76 | 77 | "Copyright" also means copyright-like laws that apply to other kinds of 78 | works, such as semiconductor masks. 79 | 80 | "The Program" refers to any copyrightable work licensed under this 81 | License. Each licensee is addressed as "you". "Licensees" and 82 | "recipients" may be individuals or organizations. 83 | 84 | To "modify" a work means to copy from or adapt all or part of the work 85 | in a fashion requiring copyright permission, other than the making of an 86 | exact copy. The resulting work is called a "modified version" of the 87 | earlier work or a work "based on" the earlier work. 88 | 89 | A "covered work" means either the unmodified Program or a work based 90 | on the Program. 91 | 92 | To "propagate" a work means to do anything with it that, without 93 | permission, would make you directly or secondarily liable for 94 | infringement under applicable copyright law, except executing it on a 95 | computer or modifying a private copy. Propagation includes copying, 96 | distribution (with or without modification), making available to the 97 | public, and in some countries other activities as well. 98 | 99 | To "convey" a work means any kind of propagation that enables other 100 | parties to make or receive copies. Mere interaction with a user through 101 | a computer network, with no transfer of a copy, is not conveying. 102 | 103 | An interactive user interface displays "Appropriate Legal Notices" 104 | to the extent that it includes a convenient and prominently visible 105 | feature that (1) displays an appropriate copyright notice, and (2) 106 | tells the user that there is no warranty for the work (except to the 107 | extent that warranties are provided), that licensees may convey the 108 | work under this License, and how to view a copy of this License. If 109 | the interface presents a list of user commands or options, such as a 110 | menu, a prominent item in the list meets this criterion. 111 | 112 | 1. Source Code. 113 | 114 | The "source code" for a work means the preferred form of the work 115 | for making modifications to it. "Object code" means any non-source 116 | form of a work. 117 | 118 | A "Standard Interface" means an interface that either is an official 119 | standard defined by a recognized standards body, or, in the case of 120 | interfaces specified for a particular programming language, one that 121 | is widely used among developers working in that language. 122 | 123 | The "System Libraries" of an executable work include anything, other 124 | than the work as a whole, that (a) is included in the normal form of 125 | packaging a Major Component, but which is not part of that Major 126 | Component, and (b) serves only to enable use of the work with that 127 | Major Component, or to implement a Standard Interface for which an 128 | implementation is available to the public in source code form. A 129 | "Major Component", in this context, means a major essential component 130 | (kernel, window system, and so on) of the specific operating system 131 | (if any) on which the executable work runs, or a compiler used to 132 | produce the work, or an object code interpreter used to run it. 133 | 134 | The "Corresponding Source" for a work in object code form means all 135 | the source code needed to generate, install, and (for an executable 136 | work) run the object code and to modify the work, including scripts to 137 | control those activities. However, it does not include the work's 138 | System Libraries, or general-purpose tools or generally available free 139 | programs which are used unmodified in performing those activities but 140 | which are not part of the work. For example, Corresponding Source 141 | includes interface definition files associated with source files for 142 | the work, and the source code for shared libraries and dynamically 143 | linked subprograms that the work is specifically designed to require, 144 | such as by intimate data communication or control flow between those 145 | subprograms and other parts of the work. 146 | 147 | The Corresponding Source need not include anything that users 148 | can regenerate automatically from other parts of the Corresponding 149 | Source. 150 | 151 | The Corresponding Source for a work in source code form is that 152 | same work. 153 | 154 | 2. Basic Permissions. 155 | 156 | All rights granted under this License are granted for the term of 157 | copyright on the Program, and are irrevocable provided the stated 158 | conditions are met. This License explicitly affirms your unlimited 159 | permission to run the unmodified Program. The output from running a 160 | covered work is covered by this License only if the output, given its 161 | content, constitutes a covered work. This License acknowledges your 162 | rights of fair use or other equivalent, as provided by copyright law. 163 | 164 | You may make, run and propagate covered works that you do not 165 | convey, without conditions so long as your license otherwise remains 166 | in force. You may convey covered works to others for the sole purpose 167 | of having them make modifications exclusively for you, or provide you 168 | with facilities for running those works, provided that you comply with 169 | the terms of this License in conveying all material for which you do 170 | not control copyright. Those thus making or running the covered works 171 | for you must do so exclusively on your behalf, under your direction 172 | and control, on terms that prohibit them from making any copies of 173 | your copyrighted material outside their relationship with you. 174 | 175 | Conveying under any other circumstances is permitted solely under 176 | the conditions stated below. Sublicensing is not allowed; section 10 177 | makes it unnecessary. 178 | 179 | 3. Protecting Users' Legal Rights From Anti-Circumvention Law. 180 | 181 | No covered work shall be deemed part of an effective technological 182 | measure under any applicable law fulfilling obligations under article 183 | 11 of the WIPO copyright treaty adopted on 20 December 1996, or 184 | similar laws prohibiting or restricting circumvention of such 185 | measures. 186 | 187 | When you convey a covered work, you waive any legal power to forbid 188 | circumvention of technological measures to the extent such circumvention 189 | is effected by exercising rights under this License with respect to 190 | the covered work, and you disclaim any intention to limit operation or 191 | modification of the work as a means of enforcing, against the work's 192 | users, your or third parties' legal rights to forbid circumvention of 193 | technological measures. 194 | 195 | 4. Conveying Verbatim Copies. 196 | 197 | You may convey verbatim copies of the Program's source code as you 198 | receive it, in any medium, provided that you conspicuously and 199 | appropriately publish on each copy an appropriate copyright notice; 200 | keep intact all notices stating that this License and any 201 | non-permissive terms added in accord with section 7 apply to the code; 202 | keep intact all notices of the absence of any warranty; and give all 203 | recipients a copy of this License along with the Program. 204 | 205 | You may charge any price or no price for each copy that you convey, 206 | and you may offer support or warranty protection for a fee. 207 | 208 | 5. Conveying Modified Source Versions. 209 | 210 | You may convey a work based on the Program, or the modifications to 211 | produce it from the Program, in the form of source code under the 212 | terms of section 4, provided that you also meet all of these conditions: 213 | 214 | a) The work must carry prominent notices stating that you modified 215 | it, and giving a relevant date. 216 | 217 | b) The work must carry prominent notices stating that it is 218 | released under this License and any conditions added under section 219 | 7. This requirement modifies the requirement in section 4 to 220 | "keep intact all notices". 221 | 222 | c) You must license the entire work, as a whole, under this 223 | License to anyone who comes into possession of a copy. This 224 | License will therefore apply, along with any applicable section 7 225 | additional terms, to the whole of the work, and all its parts, 226 | regardless of how they are packaged. This License gives no 227 | permission to license the work in any other way, but it does not 228 | invalidate such permission if you have separately received it. 229 | 230 | d) If the work has interactive user interfaces, each must display 231 | Appropriate Legal Notices; however, if the Program has interactive 232 | interfaces that do not display Appropriate Legal Notices, your 233 | work need not make them do so. 234 | 235 | A compilation of a covered work with other separate and independent 236 | works, which are not by their nature extensions of the covered work, 237 | and which are not combined with it such as to form a larger program, 238 | in or on a volume of a storage or distribution medium, is called an 239 | "aggregate" if the compilation and its resulting copyright are not 240 | used to limit the access or legal rights of the compilation's users 241 | beyond what the individual works permit. Inclusion of a covered work 242 | in an aggregate does not cause this License to apply to the other 243 | parts of the aggregate. 244 | 245 | 6. Conveying Non-Source Forms. 246 | 247 | You may convey a covered work in object code form under the terms 248 | of sections 4 and 5, provided that you also convey the 249 | machine-readable Corresponding Source under the terms of this License, 250 | in one of these ways: 251 | 252 | a) Convey the object code in, or embodied in, a physical product 253 | (including a physical distribution medium), accompanied by the 254 | Corresponding Source fixed on a durable physical medium 255 | customarily used for software interchange. 256 | 257 | b) Convey the object code in, or embodied in, a physical product 258 | (including a physical distribution medium), accompanied by a 259 | written offer, valid for at least three years and valid for as 260 | long as you offer spare parts or customer support for that product 261 | model, to give anyone who possesses the object code either (1) a 262 | copy of the Corresponding Source for all the software in the 263 | product that is covered by this License, on a durable physical 264 | medium customarily used for software interchange, for a price no 265 | more than your reasonable cost of physically performing this 266 | conveying of source, or (2) access to copy the 267 | Corresponding Source from a network server at no charge. 268 | 269 | c) Convey individual copies of the object code with a copy of the 270 | written offer to provide the Corresponding Source. This 271 | alternative is allowed only occasionally and noncommercially, and 272 | only if you received the object code with such an offer, in accord 273 | with subsection 6b. 274 | 275 | d) Convey the object code by offering access from a designated 276 | place (gratis or for a charge), and offer equivalent access to the 277 | Corresponding Source in the same way through the same place at no 278 | further charge. You need not require recipients to copy the 279 | Corresponding Source along with the object code. If the place to 280 | copy the object code is a network server, the Corresponding Source 281 | may be on a different server (operated by you or a third party) 282 | that supports equivalent copying facilities, provided you maintain 283 | clear directions next to the object code saying where to find the 284 | Corresponding Source. Regardless of what server hosts the 285 | Corresponding Source, you remain obligated to ensure that it is 286 | available for as long as needed to satisfy these requirements. 287 | 288 | e) Convey the object code using peer-to-peer transmission, provided 289 | you inform other peers where the object code and Corresponding 290 | Source of the work are being offered to the general public at no 291 | charge under subsection 6d. 292 | 293 | A separable portion of the object code, whose source code is excluded 294 | from the Corresponding Source as a System Library, need not be 295 | included in conveying the object code work. 296 | 297 | A "User Product" is either (1) a "consumer product", which means any 298 | tangible personal property which is normally used for personal, family, 299 | or household purposes, or (2) anything designed or sold for incorporation 300 | into a dwelling. In determining whether a product is a consumer product, 301 | doubtful cases shall be resolved in favor of coverage. For a particular 302 | product received by a particular user, "normally used" refers to a 303 | typical or common use of that class of product, regardless of the status 304 | of the particular user or of the way in which the particular user 305 | actually uses, or expects or is expected to use, the product. A product 306 | is a consumer product regardless of whether the product has substantial 307 | commercial, industrial or non-consumer uses, unless such uses represent 308 | the only significant mode of use of the product. 309 | 310 | "Installation Information" for a User Product means any methods, 311 | procedures, authorization keys, or other information required to install 312 | and execute modified versions of a covered work in that User Product from 313 | a modified version of its Corresponding Source. The information must 314 | suffice to ensure that the continued functioning of the modified object 315 | code is in no case prevented or interfered with solely because 316 | modification has been made. 317 | 318 | If you convey an object code work under this section in, or with, or 319 | specifically for use in, a User Product, and the conveying occurs as 320 | part of a transaction in which the right of possession and use of the 321 | User Product is transferred to the recipient in perpetuity or for a 322 | fixed term (regardless of how the transaction is characterized), the 323 | Corresponding Source conveyed under this section must be accompanied 324 | by the Installation Information. But this requirement does not apply 325 | if neither you nor any third party retains the ability to install 326 | modified object code on the User Product (for example, the work has 327 | been installed in ROM). 328 | 329 | The requirement to provide Installation Information does not include a 330 | requirement to continue to provide support service, warranty, or updates 331 | for a work that has been modified or installed by the recipient, or for 332 | the User Product in which it has been modified or installed. Access to a 333 | network may be denied when the modification itself materially and 334 | adversely affects the operation of the network or violates the rules and 335 | protocols for communication across the network. 336 | 337 | Corresponding Source conveyed, and Installation Information provided, 338 | in accord with this section must be in a format that is publicly 339 | documented (and with an implementation available to the public in 340 | source code form), and must require no special password or key for 341 | unpacking, reading or copying. 342 | 343 | 7. Additional Terms. 344 | 345 | "Additional permissions" are terms that supplement the terms of this 346 | License by making exceptions from one or more of its conditions. 347 | Additional permissions that are applicable to the entire Program shall 348 | be treated as though they were included in this License, to the extent 349 | that they are valid under applicable law. If additional permissions 350 | apply only to part of the Program, that part may be used separately 351 | under those permissions, but the entire Program remains governed by 352 | this License without regard to the additional permissions. 353 | 354 | When you convey a copy of a covered work, you may at your option 355 | remove any additional permissions from that copy, or from any part of 356 | it. (Additional permissions may be written to require their own 357 | removal in certain cases when you modify the work.) You may place 358 | additional permissions on material, added by you to a covered work, 359 | for which you have or can give appropriate copyright permission. 360 | 361 | Notwithstanding any other provision of this License, for material you 362 | add to a covered work, you may (if authorized by the copyright holders of 363 | that material) supplement the terms of this License with terms: 364 | 365 | a) Disclaiming warranty or limiting liability differently from the 366 | terms of sections 15 and 16 of this License; or 367 | 368 | b) Requiring preservation of specified reasonable legal notices or 369 | author attributions in that material or in the Appropriate Legal 370 | Notices displayed by works containing it; or 371 | 372 | c) Prohibiting misrepresentation of the origin of that material, or 373 | requiring that modified versions of such material be marked in 374 | reasonable ways as different from the original version; or 375 | 376 | d) Limiting the use for publicity purposes of names of licensors or 377 | authors of the material; or 378 | 379 | e) Declining to grant rights under trademark law for use of some 380 | trade names, trademarks, or service marks; or 381 | 382 | f) Requiring indemnification of licensors and authors of that 383 | material by anyone who conveys the material (or modified versions of 384 | it) with contractual assumptions of liability to the recipient, for 385 | any liability that these contractual assumptions directly impose on 386 | those licensors and authors. 387 | 388 | All other non-permissive additional terms are considered "further 389 | restrictions" within the meaning of section 10. If the Program as you 390 | received it, or any part of it, contains a notice stating that it is 391 | governed by this License along with a term that is a further 392 | restriction, you may remove that term. If a license document contains 393 | a further restriction but permits relicensing or conveying under this 394 | License, you may add to a covered work material governed by the terms 395 | of that license document, provided that the further restriction does 396 | not survive such relicensing or conveying. 397 | 398 | If you add terms to a covered work in accord with this section, you 399 | must place, in the relevant source files, a statement of the 400 | additional terms that apply to those files, or a notice indicating 401 | where to find the applicable terms. 402 | 403 | Additional terms, permissive or non-permissive, may be stated in the 404 | form of a separately written license, or stated as exceptions; 405 | the above requirements apply either way. 406 | 407 | 8. Termination. 408 | 409 | You may not propagate or modify a covered work except as expressly 410 | provided under this License. Any attempt otherwise to propagate or 411 | modify it is void, and will automatically terminate your rights under 412 | this License (including any patent licenses granted under the third 413 | paragraph of section 11). 414 | 415 | However, if you cease all violation of this License, then your 416 | license from a particular copyright holder is reinstated (a) 417 | provisionally, unless and until the copyright holder explicitly and 418 | finally terminates your license, and (b) permanently, if the copyright 419 | holder fails to notify you of the violation by some reasonable means 420 | prior to 60 days after the cessation. 421 | 422 | Moreover, your license from a particular copyright holder is 423 | reinstated permanently if the copyright holder notifies you of the 424 | violation by some reasonable means, this is the first time you have 425 | received notice of violation of this License (for any work) from that 426 | copyright holder, and you cure the violation prior to 30 days after 427 | your receipt of the notice. 428 | 429 | Termination of your rights under this section does not terminate the 430 | licenses of parties who have received copies or rights from you under 431 | this License. If your rights have been terminated and not permanently 432 | reinstated, you do not qualify to receive new licenses for the same 433 | material under section 10. 434 | 435 | 9. Acceptance Not Required for Having Copies. 436 | 437 | You are not required to accept this License in order to receive or 438 | run a copy of the Program. Ancillary propagation of a covered work 439 | occurring solely as a consequence of using peer-to-peer transmission 440 | to receive a copy likewise does not require acceptance. However, 441 | nothing other than this License grants you permission to propagate or 442 | modify any covered work. These actions infringe copyright if you do 443 | not accept this License. Therefore, by modifying or propagating a 444 | covered work, you indicate your acceptance of this License to do so. 445 | 446 | 10. Automatic Licensing of Downstream Recipients. 447 | 448 | Each time you convey a covered work, the recipient automatically 449 | receives a license from the original licensors, to run, modify and 450 | propagate that work, subject to this License. You are not responsible 451 | for enforcing compliance by third parties with this License. 452 | 453 | An "entity transaction" is a transaction transferring control of an 454 | organization, or substantially all assets of one, or subdividing an 455 | organization, or merging organizations. If propagation of a covered 456 | work results from an entity transaction, each party to that 457 | transaction who receives a copy of the work also receives whatever 458 | licenses to the work the party's predecessor in interest had or could 459 | give under the previous paragraph, plus a right to possession of the 460 | Corresponding Source of the work from the predecessor in interest, if 461 | the predecessor has it or can get it with reasonable efforts. 462 | 463 | You may not impose any further restrictions on the exercise of the 464 | rights granted or affirmed under this License. For example, you may 465 | not impose a license fee, royalty, or other charge for exercise of 466 | rights granted under this License, and you may not initiate litigation 467 | (including a cross-claim or counterclaim in a lawsuit) alleging that 468 | any patent claim is infringed by making, using, selling, offering for 469 | sale, or importing the Program or any portion of it. 470 | 471 | 11. Patents. 472 | 473 | A "contributor" is a copyright holder who authorizes use under this 474 | License of the Program or a work on which the Program is based. The 475 | work thus licensed is called the contributor's "contributor version". 476 | 477 | A contributor's "essential patent claims" are all patent claims 478 | owned or controlled by the contributor, whether already acquired or 479 | hereafter acquired, that would be infringed by some manner, permitted 480 | by this License, of making, using, or selling its contributor version, 481 | but do not include claims that would be infringed only as a 482 | consequence of further modification of the contributor version. For 483 | purposes of this definition, "control" includes the right to grant 484 | patent sublicenses in a manner consistent with the requirements of 485 | this License. 486 | 487 | Each contributor grants you a non-exclusive, worldwide, royalty-free 488 | patent license under the contributor's essential patent claims, to 489 | make, use, sell, offer for sale, import and otherwise run, modify and 490 | propagate the contents of its contributor version. 491 | 492 | In the following three paragraphs, a "patent license" is any express 493 | agreement or commitment, however denominated, not to enforce a patent 494 | (such as an express permission to practice a patent or covenant not to 495 | sue for patent infringement). To "grant" such a patent license to a 496 | party means to make such an agreement or commitment not to enforce a 497 | patent against the party. 498 | 499 | If you convey a covered work, knowingly relying on a patent license, 500 | and the Corresponding Source of the work is not available for anyone 501 | to copy, free of charge and under the terms of this License, through a 502 | publicly available network server or other readily accessible means, 503 | then you must either (1) cause the Corresponding Source to be so 504 | available, or (2) arrange to deprive yourself of the benefit of the 505 | patent license for this particular work, or (3) arrange, in a manner 506 | consistent with the requirements of this License, to extend the patent 507 | license to downstream recipients. "Knowingly relying" means you have 508 | actual knowledge that, but for the patent license, your conveying the 509 | covered work in a country, or your recipient's use of the covered work 510 | in a country, would infringe one or more identifiable patents in that 511 | country that you have reason to believe are valid. 512 | 513 | If, pursuant to or in connection with a single transaction or 514 | arrangement, you convey, or propagate by procuring conveyance of, a 515 | covered work, and grant a patent license to some of the parties 516 | receiving the covered work authorizing them to use, propagate, modify 517 | or convey a specific copy of the covered work, then the patent license 518 | you grant is automatically extended to all recipients of the covered 519 | work and works based on it. 520 | 521 | A patent license is "discriminatory" if it does not include within 522 | the scope of its coverage, prohibits the exercise of, or is 523 | conditioned on the non-exercise of one or more of the rights that are 524 | specifically granted under this License. You may not convey a covered 525 | work if you are a party to an arrangement with a third party that is 526 | in the business of distributing software, under which you make payment 527 | to the third party based on the extent of your activity of conveying 528 | the work, and under which the third party grants, to any of the 529 | parties who would receive the covered work from you, a discriminatory 530 | patent license (a) in connection with copies of the covered work 531 | conveyed by you (or copies made from those copies), or (b) primarily 532 | for and in connection with specific products or compilations that 533 | contain the covered work, unless you entered into that arrangement, 534 | or that patent license was granted, prior to 28 March 2007. 535 | 536 | Nothing in this License shall be construed as excluding or limiting 537 | any implied license or other defenses to infringement that may 538 | otherwise be available to you under applicable patent law. 539 | 540 | 12. No Surrender of Others' Freedom. 541 | 542 | If conditions are imposed on you (whether by court order, agreement or 543 | otherwise) that contradict the conditions of this License, they do not 544 | excuse you from the conditions of this License. If you cannot convey a 545 | covered work so as to satisfy simultaneously your obligations under this 546 | License and any other pertinent obligations, then as a consequence you may 547 | not convey it at all. For example, if you agree to terms that obligate you 548 | to collect a royalty for further conveying from those to whom you convey 549 | the Program, the only way you could satisfy both those terms and this 550 | License would be to refrain entirely from conveying the Program. 551 | 552 | 13. Use with the GNU Affero General Public License. 553 | 554 | Notwithstanding any other provision of this License, you have 555 | permission to link or combine any covered work with a work licensed 556 | under version 3 of the GNU Affero General Public License into a single 557 | combined work, and to convey the resulting work. The terms of this 558 | License will continue to apply to the part which is the covered work, 559 | but the special requirements of the GNU Affero General Public License, 560 | section 13, concerning interaction through a network will apply to the 561 | combination as such. 562 | 563 | 14. Revised Versions of this License. 564 | 565 | The Free Software Foundation may publish revised and/or new versions of 566 | the GNU General Public License from time to time. Such new versions will 567 | be similar in spirit to the present version, but may differ in detail to 568 | address new problems or concerns. 569 | 570 | Each version is given a distinguishing version number. If the 571 | Program specifies that a certain numbered version of the GNU General 572 | Public License "or any later version" applies to it, you have the 573 | option of following the terms and conditions either of that numbered 574 | version or of any later version published by the Free Software 575 | Foundation. If the Program does not specify a version number of the 576 | GNU General Public License, you may choose any version ever published 577 | by the Free Software Foundation. 578 | 579 | If the Program specifies that a proxy can decide which future 580 | versions of the GNU General Public License can be used, that proxy's 581 | public statement of acceptance of a version permanently authorizes you 582 | to choose that version for the Program. 583 | 584 | Later license versions may give you additional or different 585 | permissions. However, no additional obligations are imposed on any 586 | author or copyright holder as a result of your choosing to follow a 587 | later version. 588 | 589 | 15. Disclaimer of Warranty. 590 | 591 | THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY 592 | APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT 593 | HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY 594 | OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, 595 | THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 596 | PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM 597 | IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF 598 | ALL NECESSARY SERVICING, REPAIR OR CORRECTION. 599 | 600 | 16. Limitation of Liability. 601 | 602 | IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING 603 | WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS 604 | THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY 605 | GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE 606 | USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF 607 | DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD 608 | PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), 609 | EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF 610 | SUCH DAMAGES. 611 | 612 | 17. Interpretation of Sections 15 and 16. 613 | 614 | If the disclaimer of warranty and limitation of liability provided 615 | above cannot be given local legal effect according to their terms, 616 | reviewing courts shall apply local law that most closely approximates 617 | an absolute waiver of all civil liability in connection with the 618 | Program, unless a warranty or assumption of liability accompanies a 619 | copy of the Program in return for a fee. 620 | 621 | END OF TERMS AND CONDITIONS 622 | 623 | How to Apply These Terms to Your New Programs 624 | 625 | If you develop a new program, and you want it to be of the greatest 626 | possible use to the public, the best way to achieve this is to make it 627 | free software which everyone can redistribute and change under these terms. 628 | 629 | To do so, attach the following notices to the program. It is safest 630 | to attach them to the start of each source file to most effectively 631 | state the exclusion of warranty; and each file should have at least 632 | the "copyright" line and a pointer to where the full notice is found. 633 | 634 | 635 | Copyright (C) 636 | 637 | This program is free software: you can redistribute it and/or modify 638 | it under the terms of the GNU General Public License as published by 639 | the Free Software Foundation, either version 3 of the License, or 640 | (at your option) any later version. 641 | 642 | This program is distributed in the hope that it will be useful, 643 | but WITHOUT ANY WARRANTY; without even the implied warranty of 644 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 645 | GNU General Public License for more details. 646 | 647 | You should have received a copy of the GNU General Public License 648 | along with this program. If not, see . 649 | 650 | Also add information on how to contact you by electronic and paper mail. 651 | 652 | If the program does terminal interaction, make it output a short 653 | notice like this when it starts in an interactive mode: 654 | 655 | Copyright (C) 656 | This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. 657 | This is free software, and you are welcome to redistribute it 658 | under certain conditions; type `show c' for details. 659 | 660 | The hypothetical commands `show w' and `show c' should show the appropriate 661 | parts of the General Public License. Of course, your program's commands 662 | might be different; for a GUI interface, you would use an "about box". 663 | 664 | You should also get your employer (if you work as a programmer) or school, 665 | if any, to sign a "copyright disclaimer" for the program, if necessary. 666 | For more information on this, and how to apply and follow the GNU GPL, see 667 | . 668 | 669 | The GNU General Public License does not permit incorporating your program 670 | into proprietary programs. If your program is a subroutine library, you 671 | may consider it more useful to permit linking proprietary applications with 672 | the library. If this is what you want to do, use the GNU Lesser General 673 | Public License instead of this License. But first, please read 674 | . 675 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Annin Robot Project 2 | 3 | ## 6 axis stepper motor robot and control software 4 | 5 | This project includes: 6 | 7 | - Bill of materials and instructions 8 | - CAD files to 3D print components to build the robot 9 | - Arduino sketch for stepper driver control 10 | - Software to program and operate robot 11 | 12 | All geared stepper motors and drivers are available from [www.omc-stepperonline.com](https://www.omc-stepperonline.com/?tracking=59c1139e8987b) 13 | all other misc hardware are off the shelf items available from multiple sources (see the bill of materials file) 14 | 15 | [![Alt text](https://img.youtube.com/vi/XkAfb8alqnI/0.jpg)](https://www.youtube.com/watch?v=XkAfb8alqnI) 16 | 17 | 18 | This was my first Arduino program and my first python application using the Tk module. 19 | I hope people will enjoy building thier own robot, utilize and improve the software 20 | and design and build bigger and better robot units and share thier designs. 21 | 22 | 1. review the bill of materials 23 | 2. review the assembly instructions 24 | 3. download models and build robot 25 | 4. review calibration video [Calibration Video](https://youtu.be/jC1Iq60EnBI) 26 | 5. review programming video [Programming Video](https://youtu.be/hFJe0j0nB_w) 27 | 28 | please view license file 29 | 30 | Questions: chris.annin@gmail.com 31 | # 32 | [![Donate](https://img.shields.io/badge/Donate-PayPal-green.svg)](https://www.paypal.me/ChrisAnnin) 33 | -------------------------------------------------------------------------------- /STL files/Arduino Mount.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Arduino Mount.STL -------------------------------------------------------------------------------- /STL files/Collar 1 inch.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Collar 1 inch.STL -------------------------------------------------------------------------------- /STL files/Gear J5 ring carrier cap.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Gear J5 ring carrier cap.STL -------------------------------------------------------------------------------- /STL files/Gear J5 ring carrier.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Gear J5 ring carrier.STL -------------------------------------------------------------------------------- /STL files/Gear J5 worm bushing.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Gear J5 worm bushing.STL -------------------------------------------------------------------------------- /STL files/Gripper Cover side plate.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Gripper Cover side plate.STL -------------------------------------------------------------------------------- /STL files/Gripper Motor side plate.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Gripper Motor side plate.STL -------------------------------------------------------------------------------- /STL files/Gripper center spur.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Gripper center spur.STL -------------------------------------------------------------------------------- /STL files/Gripper left jaw.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Gripper left jaw.STL -------------------------------------------------------------------------------- /STL files/Gripper right jaw.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Gripper right jaw.STL -------------------------------------------------------------------------------- /STL files/Home cradle.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Home cradle.STL -------------------------------------------------------------------------------- /STL files/J1 Alignment Ring.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J1 Alignment Ring.STL -------------------------------------------------------------------------------- /STL files/J1 Base.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J1 Base.STL -------------------------------------------------------------------------------- /STL files/J1 Turret cover.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J1 Turret cover.STL -------------------------------------------------------------------------------- /STL files/J1 Turret.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J1 Turret.STL -------------------------------------------------------------------------------- /STL files/J2 Arm Cover.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 Arm Cover.STL -------------------------------------------------------------------------------- /STL files/J2 Arm Left.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 Arm Left.STL -------------------------------------------------------------------------------- /STL files/J2 Arm Right.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 Arm Right.STL -------------------------------------------------------------------------------- /STL files/J2 Drive Block.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 Drive Block.STL -------------------------------------------------------------------------------- /STL files/J2 Drive Rod Support Block.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 Drive Rod Support Block.STL -------------------------------------------------------------------------------- /STL files/J2 Motor Support.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 Motor Support.STL -------------------------------------------------------------------------------- /STL files/J2 Spacer 2.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 Spacer 2.STL -------------------------------------------------------------------------------- /STL files/J2 Spacer.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 Spacer.STL -------------------------------------------------------------------------------- /STL files/J2 nut cap.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J2 nut cap.STL -------------------------------------------------------------------------------- /STL files/J3 Spindle.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J3 Spindle.STL -------------------------------------------------------------------------------- /STL files/J3 Turret cap.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J3 Turret cap.STL -------------------------------------------------------------------------------- /STL files/J3 Turret.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J3 Turret.STL -------------------------------------------------------------------------------- /STL files/J4 Boom left.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J4 Boom left.STL -------------------------------------------------------------------------------- /STL files/J4 Boom right.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J4 Boom right.STL -------------------------------------------------------------------------------- /STL files/J4 Boom.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J4 Boom.STL -------------------------------------------------------------------------------- /STL files/J4 Collar 1 inch.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J4 Collar 1 inch.STL -------------------------------------------------------------------------------- /STL files/J4 wire holder.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J4 wire holder.STL -------------------------------------------------------------------------------- /STL files/J5 Clevis Center.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Clevis Center.STL -------------------------------------------------------------------------------- /STL files/J5 Clevis Left Arm.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Clevis Left Arm.STL -------------------------------------------------------------------------------- /STL files/J5 Clevis Right Arm.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Clevis Right Arm.STL -------------------------------------------------------------------------------- /STL files/J5 Clevis.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Clevis.STL -------------------------------------------------------------------------------- /STL files/J5 Motor Mount.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Motor Mount.STL -------------------------------------------------------------------------------- /STL files/J5 Turret Center.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Turret Center.STL -------------------------------------------------------------------------------- /STL files/J5 Turret Left Arm.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Turret Left Arm.STL -------------------------------------------------------------------------------- /STL files/J5 Turret Right Arm.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Turret Right Arm.STL -------------------------------------------------------------------------------- /STL files/J5 Turret.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/J5 Turret.STL -------------------------------------------------------------------------------- /STL files/Mouse Holder.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/Mouse Holder.STL -------------------------------------------------------------------------------- /STL files/coupler.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/coupler.STL -------------------------------------------------------------------------------- /STL files/timing belt coupler.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/STL files/timing belt coupler.STL -------------------------------------------------------------------------------- /STL files/~$J2 Arm Cover.SLDPRT: -------------------------------------------------------------------------------- 1 | CAnnin -------------------------------------------------------------------------------- /Software Executable/Annin_Robot_EXE.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/Software Executable/Annin_Robot_EXE.zip -------------------------------------------------------------------------------- /Software Source Code/ARbot.cal: -------------------------------------------------------------------------------- 1 | (S'0' 2 | p0 3 | S'20000' 4 | p1 5 | g0 6 | S'360' 7 | p2 8 | S'0.018' 9 | p3 10 | S'180' 11 | p4 12 | S'10000' 13 | p5 14 | S'180.0' 15 | p6 16 | S'200' 17 | p7 18 | g0 19 | S'20000' 20 | p8 21 | g0 22 | S'360' 23 | p9 24 | S'0.018' 25 | p10 26 | S'180' 27 | p11 28 | S'10000' 29 | p12 30 | S'180.0' 31 | p13 32 | S'200' 33 | p14 34 | g0 35 | S'20000' 36 | p15 37 | g0 38 | S'360' 39 | p16 40 | S'0.018' 41 | p17 42 | S'180' 43 | p18 44 | S'10000' 45 | p19 46 | S'180.0' 47 | p20 48 | S'200' 49 | p21 50 | g0 51 | S'20000' 52 | p22 53 | g0 54 | S'360' 55 | p23 56 | S'0.018' 57 | p24 58 | S'180' 59 | p25 60 | S'10000' 61 | p26 62 | S'180.0' 63 | p27 64 | S'200' 65 | p28 66 | g0 67 | S'20000' 68 | p29 69 | g0 70 | S'360' 71 | p30 72 | S'0.018' 73 | p31 74 | S'180' 75 | p32 76 | S'10000' 77 | p33 78 | S'180.0' 79 | p34 80 | S'200' 81 | p35 82 | g0 83 | S'20000' 84 | p36 85 | g0 86 | S'360' 87 | p37 88 | S'0.018' 89 | p38 90 | S'180' 91 | p39 92 | S'10000' 93 | p40 94 | S'180.0' 95 | p41 96 | S'200' 97 | p42 98 | S'1' 99 | p43 100 | S'new' 101 | p44 102 | g0 103 | S'180' 104 | p45 105 | g0 106 | S'180' 107 | p46 108 | g0 109 | S'180' 110 | p47 111 | g0 112 | S'180' 113 | p48 114 | tp49 115 | . -------------------------------------------------------------------------------- /Software Source Code/ARbot.ico: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/Software Source Code/ARbot.ico -------------------------------------------------------------------------------- /Software Source Code/Annin Robot.py: -------------------------------------------------------------------------------- 1 | ########################################################################## 2 | ########################################################################## 3 | """ Annin Robot - Stepper motor robot control software 4 | Copyright (C) 2016 Chris Annin 5 | 6 | This program is free software: you can redistribute it and/or modify 7 | it under the terms of the GNU General Public License as published by 8 | the Free Software Foundation, either version 3 of the License, or 9 | any later version. 10 | 11 | This program is distributed in the hope that it will be useful, 12 | but WITHOUT ANY WARRANTY; without even the implied warranty of 13 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 14 | GNU General Public License for more details. 15 | 16 | You should have received a copy of the GNU General Public License 17 | along with this program. If not, see . 18 | 19 | chris.annin@gmail.com 20 | """ 21 | ########################################################################## 22 | ########################################################################## 23 | 24 | 25 | from Tkinter import * 26 | import pickle 27 | import serial 28 | import time 29 | import threading 30 | import Queue 31 | 32 | root = Tk() 33 | root.wm_title("Annin Robot 1.0") 34 | root.iconbitmap(r'ARbot.ico') 35 | root.resizable(width=True, height=True) 36 | root.geometry('{}x{}'.format(1024,700)) 37 | root.runTrue = 0 38 | 39 | 40 | ###DEFS################################################################### 41 | ########################################################################## 42 | 43 | 44 | def setCom(): 45 | global ser 46 | port = "COM" + comPortEntryField.get() 47 | baud = 9600 48 | ser = serial.Serial(port, baud) 49 | 50 | def deleteitem(): 51 | selRow = root.progView.curselection()[0] 52 | selection = root.progView.curselection() 53 | root.progView.delete(selection[0]) 54 | root.progView.select_set(selRow) 55 | value=root.progView.get(0,END) 56 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 57 | 58 | 59 | def executeRow(): 60 | selRow = root.progView.curselection()[0] 61 | root.progView.see(selRow+2) 62 | data = map(int, root.progView.curselection()) 63 | command=root.progView.get(data[0]) 64 | cmdType=command[:6] 65 | ##Call Program## 66 | if (cmdType == "Call P"): 67 | root.lastRow = root.progView.curselection()[0] 68 | root.lastProg = ProgEntryField.get() 69 | programIndex = command.find("Program -") 70 | progNum = str(command[programIndex+10:]) 71 | ProgEntryField.delete(0, 'end') 72 | ProgEntryField.insert(0,progNum) 73 | loadProg() 74 | time.sleep(.2) 75 | index = 0 76 | root.progView.selection_clear(0, END) 77 | root.progView.select_set(index) 78 | ##Return Program## 79 | if (cmdType == "Return"): 80 | lastRow = root.lastRow 81 | lastProg = root.lastProg 82 | ProgEntryField.delete(0, 'end') 83 | ProgEntryField.insert(0,lastProg) 84 | loadProg() 85 | time.sleep(.2) 86 | index = 0 87 | root.progView.selection_clear(0, END) 88 | root.progView.select_set(lastRow) 89 | ##Servo Command## 90 | if (cmdType == "Servo "): 91 | servoIndex = command.find("number ") 92 | posIndex = command.find("position: ") 93 | servoNum = str(command[servoIndex+7:posIndex-4]) 94 | servoPos = str(command[posIndex+10:]) 95 | command = "SV"+servoNum+"P"+servoPos 96 | ser.write(command +"\n") 97 | ser.flushInput() 98 | time.sleep(.1) 99 | ser.read() 100 | ##If Input On Jump to Tab## 101 | if (cmdType == "If On "): 102 | inputIndex = command.find("Input-") 103 | tabIndex = command.find("Tab-") 104 | inputNum = str(command[inputIndex+6:tabIndex-9]) 105 | tabNum = str(command[tabIndex+4:]) 106 | command = "JFX"+inputNum+"T"+tabNum 107 | ser.write(command +"\n") 108 | ser.flushInput() 109 | value = ser.readline() 110 | #value = str(value[3:]) 111 | manEntryField.delete(0, 'end') 112 | manEntryField.insert(0,value) 113 | if (value == "True\n"): 114 | index = root.progView.get(0, "end").index("Tab Number " + tabNum) 115 | index = index-1 116 | root.progView.selection_clear(0, END) 117 | root.progView.select_set(index) 118 | ##If Input Off Jump to Tab## 119 | if (cmdType == "If Off"): 120 | inputIndex = command.find("Input-") 121 | tabIndex = command.find("Tab-") 122 | inputNum = str(command[inputIndex+6:tabIndex-9]) 123 | tabNum = str(command[tabIndex+4:]) 124 | command = "JFX"+inputNum+"T"+tabNum 125 | ser.write(command +"\n") 126 | ser.flushInput() 127 | value = ser.readline() 128 | #value = str(value[3:]) 129 | manEntryField.delete(0, 'end') 130 | manEntryField.insert(0,value) 131 | if (value == "False\n"): 132 | index = root.progView.get(0, "end").index("Tab Number " + tabNum) 133 | index = index-1 134 | root.progView.selection_clear(0, END) 135 | root.progView.select_set(index) 136 | ##Jump to Row## 137 | if (cmdType == "Jump T"): 138 | tabIndex = command.find("Tab-") 139 | tabNum = str(command[tabIndex+4:]) 140 | index = root.progView.get(0, "end").index("Tab Number " + tabNum) 141 | root.progView.selection_clear(0, END) 142 | root.progView.select_set(index) 143 | ##Set Output ON Command## 144 | if (cmdType == "Out On"): 145 | outputIndex = command.find("Output-") 146 | outputNum = str(command[outputIndex+7:]) 147 | command = "ONX"+outputNum 148 | ser.write(command +"\n") 149 | ser.flushInput() 150 | time.sleep(.1) 151 | ser.read() 152 | ##Set Output OFF Command## 153 | if (cmdType == "Out Of"): 154 | outputIndex = command.find("Output-") 155 | outputNum = str(command[outputIndex+7:]) 156 | command = "OFX"+outputNum 157 | ser.write(command +"\n") 158 | ser.flushInput() 159 | time.sleep(.1) 160 | ser.read() 161 | ##Wait Input ON Command## 162 | if (cmdType == "Wait I"): 163 | inputIndex = command.find("Input-") 164 | inputNum = str(command[inputIndex+6:]) 165 | command = "WIN"+inputNum 166 | ser.write(command +"\n") 167 | ser.flushInput() 168 | time.sleep(.1) 169 | ser.read() 170 | ##Wait Input OFF Command## 171 | if (cmdType == "Wait O"): 172 | inputIndex = command.find("Input-") 173 | inputNum = str(command[inputIndex+6:]) 174 | command = "WON"+inputNum 175 | ser.write(command +"\n") 176 | ser.flushInput() 177 | time.sleep(.1) 178 | ser.read() 179 | ##Wait Time Command## 180 | if (cmdType == "Wait T"): 181 | timeIndex = command.find("Seconds-") 182 | timeSeconds = str(command[timeIndex+8:]) 183 | command = "WTS"+timeSeconds 184 | ser.write(command +"\n") 185 | ser.flushInput() 186 | time.sleep(.1) 187 | ser.read() 188 | ##Move Command## 189 | if (cmdType == "Move J"): 190 | J1curAng = J1curAngEntryField.get() 191 | J2curAng = J2curAngEntryField.get() 192 | J3curAng = J3curAngEntryField.get() 193 | J4curAng = J4curAngEntryField.get() 194 | J5curAng = J5curAngEntryField.get() 195 | J6curAng = J6curAngEntryField.get() 196 | J1newIndex = command.find("J1-") 197 | J2newIndex = command.find("J2-") 198 | J3newIndex = command.find("J3-") 199 | J4newIndex = command.find("J4-") 200 | J5newIndex = command.find("J5-") 201 | J6newIndex = command.find("J6-") 202 | SpeedIndex = command.find("Speed-") 203 | J1newAng = command[J1newIndex+3:J2newIndex-1] 204 | J2newAng = command[J2newIndex+3:J3newIndex-1] 205 | J3newAng = command[J3newIndex+3:J4newIndex-1] 206 | J4newAng = command[J4newIndex+3:J5newIndex-1] 207 | J5newAng = command[J5newIndex+3:J6newIndex-1] 208 | J6newAng = command[J6newIndex+3:SpeedIndex-1] 209 | newSpeed = str(command[SpeedIndex+6:]) 210 | ##J1 calc## 211 | J1degStep = float(J1degPerStepEntryField.get()) 212 | J1curStep = int(J1curStepEntryField.get()) 213 | if (float(J1newAng) >= float(J1curAng)): 214 | ####SET DIRECTION 215 | J1dir = "1" 216 | J1calcAng = float(J1newAng) - float(J1curAng) 217 | J1steps = int(J1calcAng / J1degStep) 218 | J1newSteps = J1curStep + J1steps 219 | J1curStepEntryField.delete(0, 'end') 220 | J1curStepEntryField.insert(0,str(J1newSteps)) 221 | J1writeAng = float(J1curAng) + J1calcAng 222 | J1curAngEntryField.delete(0, 'end') 223 | J1curAngEntryField.insert(0,str(J1writeAng)) 224 | J1steps = str(J1steps) 225 | elif(float(J1newAng) < float(J1curAng)): 226 | J1dir = "0" 227 | J1calcAng = float(J1curAng) - float(J1newAng) 228 | J1steps = int(J1calcAng / J1degStep) 229 | J1newSteps = J1curStep - J1steps 230 | J1curStepEntryField.delete(0, 'end') 231 | J1curStepEntryField.insert(0,str(J1newSteps)) 232 | J1writeAng = float(J1curAng) - J1calcAng 233 | J1curAngEntryField.delete(0, 'end') 234 | J1curAngEntryField.insert(0,str(J1writeAng)) 235 | J1steps = str(J1steps) 236 | ##J2 calc## 237 | J2degStep = float(J2degPerStepEntryField.get()) 238 | J2curStep = int(J2curStepEntryField.get()) 239 | if (float(J2newAng) >= float(J2curAng)): 240 | ####SET DIRECTION 241 | J2dir = "0" 242 | J2calcAng = float(J2newAng) - float(J2curAng) 243 | J2steps = int(J2calcAng / J2degStep) 244 | J2newSteps = J2curStep + J2steps 245 | J2curStepEntryField.delete(0, 'end') 246 | J2curStepEntryField.insert(0,str(J2newSteps)) 247 | J2writeAng = float(J2curAng) +J2calcAng 248 | J2curAngEntryField.delete(0, 'end') 249 | J2curAngEntryField.insert(0,str(J2writeAng)) 250 | J2steps = str(J2steps) 251 | elif(float(J2newAng) < float(J2curAng)): 252 | J2dir = "1" 253 | J2calcAng = float(J2curAng) - float(J2newAng) 254 | J2steps = int(J2calcAng / J2degStep) 255 | J2newSteps = J2curStep - J2steps 256 | J2curStepEntryField.delete(0, 'end') 257 | J2curStepEntryField.insert(0,str(J2newSteps)) 258 | J2writeAng = float(J2curAng) - J2calcAng 259 | J2curAngEntryField.delete(0, 'end') 260 | J2curAngEntryField.insert(0,str(J2writeAng)) 261 | J2steps = str(J2steps) 262 | ##J3 calc## 263 | J3degStep = float(J3degPerStepEntryField.get()) 264 | J3curStep = int(J3curStepEntryField.get()) 265 | if (float(J3newAng) >= float(J3curAng)): 266 | ####SET DIRECTION 267 | J3dir = "0" 268 | J3calcAng = float(J3newAng) - float(J3curAng) 269 | J3steps = int(J3calcAng / J3degStep) 270 | J3newSteps = J3curStep + J3steps 271 | J3curStepEntryField.delete(0, 'end') 272 | J3curStepEntryField.insert(0,str(J3newSteps)) 273 | J3writeAng = float(J3curAng) + J3calcAng 274 | J3curAngEntryField.delete(0, 'end') 275 | J3curAngEntryField.insert(0,str(J3writeAng)) 276 | J3steps = str(J3steps) 277 | elif(float(J3newAng) < float(J3curAng)): 278 | J3dir = "1" 279 | J3calcAng = float(J3curAng) - float(J3newAng) 280 | J3steps = int(J3calcAng / J3degStep) 281 | J3newSteps = J3curStep - J3steps 282 | J3curStepEntryField.delete(0, 'end') 283 | J3curStepEntryField.insert(0,str(J3newSteps)) 284 | J3writeAng = float(J3curAng) - J3calcAng 285 | J3curAngEntryField.delete(0, 'end') 286 | J3curAngEntryField.insert(0,str(J3writeAng)) 287 | J3steps = str(J3steps) 288 | ##J4 calc## 289 | J4degStep = float(J4degPerStepEntryField.get()) 290 | J4curStep = int(J4curStepEntryField.get()) 291 | if (float(J4newAng) >= float(J4curAng)): 292 | ####SET DIRECTION 293 | J4dir = "0" 294 | J4calcAng = float(J4newAng) - float(J4curAng) 295 | J4steps = int(J4calcAng / J4degStep) 296 | J4newSteps = J4curStep + J4steps 297 | J4curStepEntryField.delete(0, 'end') 298 | J4curStepEntryField.insert(0,str(J4newSteps)) 299 | J4writeAng = float(J4curAng) + J4calcAng 300 | J4curAngEntryField.delete(0, 'end') 301 | J4curAngEntryField.insert(0,str(J4writeAng)) 302 | J4steps = str(J4steps) 303 | elif(float(J4newAng) < float(J4curAng)): 304 | J4dir = "1" 305 | J4calcAng = float(J4curAng) - float(J4newAng) 306 | J4steps = int(J4calcAng / J4degStep) 307 | J4newSteps = J4curStep - J4steps 308 | J4curStepEntryField.delete(0, 'end') 309 | J4curStepEntryField.insert(0,str(J4newSteps)) 310 | J4writeAng = float(J4curAng) - J4calcAng 311 | J4curAngEntryField.delete(0, 'end') 312 | J4curAngEntryField.insert(0,str(J4writeAng)) 313 | J4steps = str(J4steps) 314 | ##J5 calc## 315 | J5degStep = float(J5degPerStepEntryField.get()) 316 | J5curStep = int(J5curStepEntryField.get()) 317 | if (float(J5newAng) >= float(J5curAng)): 318 | ####SET DIRECTION 319 | J5dir = "1" 320 | J5calcAng = float(J5newAng) - float(J5curAng) 321 | J5steps = int(J5calcAng / J5degStep) 322 | J5newSteps = J5curStep + J5steps 323 | J5curStepEntryField.delete(0, 'end') 324 | J5curStepEntryField.insert(0,str(J5newSteps)) 325 | J5writeAng = float(J5curAng) + J5calcAng 326 | J5curAngEntryField.delete(0, 'end') 327 | J5curAngEntryField.insert(0,str(J5writeAng)) 328 | J5steps = str(J5steps) 329 | elif(float(J5newAng) < float(J5curAng)): 330 | J5dir = "0" 331 | J5calcAng = float(J5curAng) - float(J5newAng) 332 | J5steps = int(J5calcAng / J5degStep) 333 | J5newSteps = J5curStep - J5steps 334 | J5curStepEntryField.delete(0, 'end') 335 | J5curStepEntryField.insert(0,str(J5newSteps)) 336 | J5writeAng = float(J5curAng) - J5calcAng 337 | J5curAngEntryField.delete(0, 'end') 338 | J5curAngEntryField.insert(0,str(J5writeAng)) 339 | J5steps = str(J5steps) 340 | ##J6 calc## 341 | J6degStep = float(J6degPerStepEntryField.get()) 342 | J6curStep = int(J6curStepEntryField.get()) 343 | if (float(J6newAng) >= float(J6curAng)): 344 | ####SET DIRECTION 345 | J6dir = "0" 346 | J6calcAng = float(J6newAng) - float(J6curAng) 347 | J6steps = int(J6calcAng / J6degStep) 348 | J6newSteps = J6curStep + J6steps 349 | J6curStepEntryField.delete(0, 'end') 350 | J6curStepEntryField.insert(0,str(J6newSteps)) 351 | J6writeAng = float(J6curAng) + J6calcAng 352 | J6curAngEntryField.delete(0, 'end') 353 | J6curAngEntryField.insert(0,str(J6writeAng)) 354 | J6steps = str(J6steps) 355 | elif(float(J6newAng) < float(J6curAng)): 356 | J6dir = "1" 357 | J6calcAng = float(J6curAng) - float(J6newAng) 358 | J6steps = int(J6calcAng / J6degStep) 359 | J6newSteps = J6curStep - J6steps 360 | J6curStepEntryField.delete(0, 'end') 361 | J6curStepEntryField.insert(0,str(J6newSteps)) 362 | J6writeAng = float(J6curAng) - J6calcAng 363 | J6curAngEntryField.delete(0, 'end') 364 | J6curAngEntryField.insert(0,str(J6writeAng)) 365 | J6steps = str(J6steps) 366 | commandCalc = "MJA"+J1dir+J1steps+"B"+J2dir+J2steps+"C"+J3dir+J3steps+"D"+J4dir+J4steps+"E"+J5dir+J5steps+"F"+J6dir+J6steps+"S"+newSpeed 367 | ser.write(commandCalc +"\n") 368 | ser.flushInput() 369 | time.sleep(.1) 370 | ser.read() 371 | savePosData() 372 | 373 | 374 | 375 | def stepFwd(): 376 | executeRow() 377 | selRow = root.progView.curselection()[0] 378 | root.progView.selection_clear(0, END) 379 | selRow += 1 380 | root.progView.select_set(selRow) 381 | time.sleep(.1) 382 | try: 383 | selRow = root.progView.curselection()[0] 384 | curRowEntryField.delete(0, 'end') 385 | curRowEntryField.insert(0,selRow) 386 | except: 387 | curRowEntryField.delete(0, 'end') 388 | curRowEntryField.insert(0,"---") 389 | 390 | 391 | def stepRev(): 392 | executeRow() 393 | selRow = root.progView.curselection()[0] 394 | root.progView.selection_clear(0, END) 395 | selRow -= 1 396 | root.progView.select_set(selRow) 397 | time.sleep(.1) 398 | try: 399 | selRow = root.progView.curselection()[0] 400 | curRowEntryField.delete(0, 'end') 401 | curRowEntryField.insert(0,selRow) 402 | except: 403 | curRowEntryField.delete(0, 'end') 404 | curRowEntryField.insert(0,"---") 405 | 406 | 407 | def runProg(): 408 | def threadProg(): 409 | try: 410 | curRow = root.progView.curselection()[0] 411 | if (curRow == 0): 412 | curRow=1 413 | except: 414 | curRow=1 415 | root.progView.selection_clear(0, END) 416 | root.progView.select_set(curRow) 417 | root.runTrue = 1 418 | while root.runTrue == 1: 419 | if (root.runTrue == 0): 420 | runStatusLab.config(text='PROGRAM STOPPED', bg = "red") 421 | else: 422 | runStatusLab.config(text='PROGRAM RUNNING', bg = "green") 423 | executeRow() 424 | selRow = root.progView.curselection()[0] 425 | root.progView.selection_clear(0, END) 426 | selRow += 1 427 | root.progView.select_set(selRow) 428 | curRow += 1 429 | time.sleep(.1) 430 | try: 431 | selRow = root.progView.curselection()[0] 432 | curRowEntryField.delete(0, 'end') 433 | curRowEntryField.insert(0,selRow) 434 | except: 435 | curRowEntryField.delete(0, 'end') 436 | curRowEntryField.insert(0,"---") 437 | root.runTrue = 0 438 | runStatusLab.config(text='PROGRAM STOPPED', bg = "red") 439 | t = threading.Thread(target=threadProg) 440 | t.start() 441 | 442 | 443 | def stopProg(): 444 | root.runTrue = 0 445 | if (root.runTrue == 0): 446 | runStatusLab.config(text='PROGRAM STOPPED', bg = "red") 447 | else: 448 | runStatusLab.config(text='PROGRAM RUNNING', bg = "green") 449 | 450 | def calRobot(): 451 | calibration.delete(0, END) 452 | ##J1## 453 | J1stepLimNeg = float(J1stepLimNegEntryField.get()) 454 | J1stepLimPos = float(J1stepLimPosEntryField.get()) 455 | J1angLimNeg = float(J1angLimNegEntryField.get()) 456 | J1angLimPos = float(J1angLimPosEntryField.get()) 457 | J1stepDelta = J1stepLimPos - J1stepLimNeg 458 | J1angDelta = J1angLimPos - J1angLimNeg 459 | J1degPerStep = J1angDelta / J1stepDelta 460 | J1degPerStepEntryField.delete(0, 'end') 461 | J1degPerStepEntryField.insert(0,str(J1degPerStep)) 462 | J1calAng = float(J1calAngleEntryField.get()) 463 | J1curStep = int((J1calAng-J1angLimNeg) / J1degPerStep) 464 | J1curStepEntryField.delete(0, 'end') 465 | J1curStepEntryField.insert(0,str(J1curStep)) 466 | J1curAngEntryField.delete(0, 'end') 467 | J1curAngEntryField.insert(0,str(J1calAng)) 468 | ########### 469 | calibration.insert(END, J1stepLimNegEntryField.get()) 470 | calibration.insert(END, J1stepLimPosEntryField.get()) 471 | calibration.insert(END, J1angLimNegEntryField.get()) 472 | calibration.insert(END, J1angLimPosEntryField.get()) 473 | calibration.insert(END, J1degPerStepEntryField.get()) 474 | calibration.insert(END, J1calAngleEntryField.get()) 475 | calibration.insert(END, J1curStepEntryField.get()) 476 | calibration.insert(END, J1curAngEntryField.get()) 477 | calibration.insert(END, J1jogStepsEntryField.get()) 478 | ########### 479 | ##J2## 480 | J2stepLimNeg = float(J2stepLimNegEntryField.get()) 481 | J2stepLimPos = float(J2stepLimPosEntryField.get()) 482 | J2angLimNeg = float(J2angLimNegEntryField.get()) 483 | J2angLimPos = float(J2angLimPosEntryField.get()) 484 | J2stepDelta = J2stepLimPos - J2stepLimNeg 485 | J2angDelta = J2angLimPos - J2angLimNeg 486 | J2degPerStep = J2angDelta / J2stepDelta 487 | J2degPerStepEntryField.delete(0, 'end') 488 | J2degPerStepEntryField.insert(0,str(J2degPerStep)) 489 | J2calAng = float(J2calAngleEntryField.get()) 490 | J2curStep = int((J2calAng-J2angLimNeg) / J2degPerStep) 491 | J2curStepEntryField.delete(0, 'end') 492 | J2curStepEntryField.insert(0,str(J2curStep)) 493 | J2curAngEntryField.delete(0, 'end') 494 | J2curAngEntryField.insert(0,str(J2calAng)) 495 | ########### 496 | calibration.insert(END, J2stepLimNegEntryField.get()) 497 | calibration.insert(END, J2stepLimPosEntryField.get()) 498 | calibration.insert(END, J2angLimNegEntryField.get()) 499 | calibration.insert(END, J2angLimPosEntryField.get()) 500 | calibration.insert(END, J2degPerStepEntryField.get()) 501 | calibration.insert(END, J2calAngleEntryField.get()) 502 | calibration.insert(END, J2curStepEntryField.get()) 503 | calibration.insert(END, J2curAngEntryField.get()) 504 | calibration.insert(END, J2jogStepsEntryField.get()) 505 | ########### 506 | ##J3## 507 | J3stepLimNeg = float(J3stepLimNegEntryField.get()) 508 | J3stepLimPos = float(J3stepLimPosEntryField.get()) 509 | J3angLimNeg = float(J3angLimNegEntryField.get()) 510 | J3angLimPos = float(J3angLimPosEntryField.get()) 511 | J3stepDelta = J3stepLimPos - J3stepLimNeg 512 | J3angDelta = J3angLimPos - J3angLimNeg 513 | J3degPerStep = J3angDelta / J3stepDelta 514 | J3degPerStepEntryField.delete(0, 'end') 515 | J3degPerStepEntryField.insert(0,str(J3degPerStep)) 516 | J3calAng = float(J3calAngleEntryField.get()) 517 | J3curStep = int((J3calAng-J3angLimNeg) / J3degPerStep) 518 | J3curStepEntryField.delete(0, 'end') 519 | J3curStepEntryField.insert(0,str(J3curStep)) 520 | J3curAngEntryField.delete(0, 'end') 521 | J3curAngEntryField.insert(0,str(J3calAng)) 522 | ########### 523 | calibration.insert(END, J3stepLimNegEntryField.get()) 524 | calibration.insert(END, J3stepLimPosEntryField.get()) 525 | calibration.insert(END, J3angLimNegEntryField.get()) 526 | calibration.insert(END, J3angLimPosEntryField.get()) 527 | calibration.insert(END, J3degPerStepEntryField.get()) 528 | calibration.insert(END, J3calAngleEntryField.get()) 529 | calibration.insert(END, J3curStepEntryField.get()) 530 | calibration.insert(END, J3curAngEntryField.get()) 531 | calibration.insert(END, J3jogStepsEntryField.get()) 532 | ########### 533 | ##J4## 534 | J4stepLimNeg = float(J4stepLimNegEntryField.get()) 535 | J4stepLimPos = float(J4stepLimPosEntryField.get()) 536 | J4angLimNeg = float(J4angLimNegEntryField.get()) 537 | J4angLimPos = float(J4angLimPosEntryField.get()) 538 | J4stepDelta = J4stepLimPos - J4stepLimNeg 539 | J4angDelta = J4angLimPos - J4angLimNeg 540 | J4degPerStep = J4angDelta / J4stepDelta 541 | J4degPerStepEntryField.delete(0, 'end') 542 | J4degPerStepEntryField.insert(0,str(J4degPerStep)) 543 | J4calAng = float(J4calAngleEntryField.get()) 544 | J4curStep = int((J4calAng-J4angLimNeg) / J4degPerStep) 545 | J4curStepEntryField.delete(0, 'end') 546 | J4curStepEntryField.insert(0,str(J4curStep)) 547 | J4curAngEntryField.delete(0, 'end') 548 | J4curAngEntryField.insert(0,str(J4calAng)) 549 | ########### 550 | calibration.insert(END, J4stepLimNegEntryField.get()) 551 | calibration.insert(END, J4stepLimPosEntryField.get()) 552 | calibration.insert(END, J4angLimNegEntryField.get()) 553 | calibration.insert(END, J4angLimPosEntryField.get()) 554 | calibration.insert(END, J4degPerStepEntryField.get()) 555 | calibration.insert(END, J4calAngleEntryField.get()) 556 | calibration.insert(END, J4curStepEntryField.get()) 557 | calibration.insert(END, J4curAngEntryField.get()) 558 | calibration.insert(END, J4jogStepsEntryField.get()) 559 | ########### 560 | ##J5## 561 | J5stepLimNeg = float(J5stepLimNegEntryField.get()) 562 | J5stepLimPos = float(J5stepLimPosEntryField.get()) 563 | J5angLimNeg = float(J5angLimNegEntryField.get()) 564 | J5angLimPos = float(J5angLimPosEntryField.get()) 565 | J5stepDelta = J5stepLimPos - J5stepLimNeg 566 | J5angDelta = J5angLimPos - J5angLimNeg 567 | J5degPerStep = J5angDelta / J5stepDelta 568 | J5degPerStepEntryField.delete(0, 'end') 569 | J5degPerStepEntryField.insert(0,str(J5degPerStep)) 570 | J5calAng = float(J5calAngleEntryField.get()) 571 | J5curStep = int((J5calAng-J5angLimNeg) / J5degPerStep) 572 | J5curStepEntryField.delete(0, 'end') 573 | J5curStepEntryField.insert(0,str(J5curStep)) 574 | J5curAngEntryField.delete(0, 'end') 575 | J5curAngEntryField.insert(0,str(J5calAng)) 576 | ########### 577 | calibration.insert(END, J5stepLimNegEntryField.get()) 578 | calibration.insert(END, J5stepLimPosEntryField.get()) 579 | calibration.insert(END, J5angLimNegEntryField.get()) 580 | calibration.insert(END, J5angLimPosEntryField.get()) 581 | calibration.insert(END, J5degPerStepEntryField.get()) 582 | calibration.insert(END, J5calAngleEntryField.get()) 583 | calibration.insert(END, J5curStepEntryField.get()) 584 | calibration.insert(END, J5curAngEntryField.get()) 585 | calibration.insert(END, J5jogStepsEntryField.get()) 586 | ########### 587 | ##J6## 588 | J6stepLimNeg = float(J6stepLimNegEntryField.get()) 589 | J6stepLimPos = float(J6stepLimPosEntryField.get()) 590 | J6angLimNeg = float(J6angLimNegEntryField.get()) 591 | J6angLimPos = float(J6angLimPosEntryField.get()) 592 | J6stepDelta = J6stepLimPos - J6stepLimNeg 593 | J6angDelta = J6angLimPos - J6angLimNeg 594 | J6degPerStep = J6angDelta / J6stepDelta 595 | J6degPerStepEntryField.delete(0, 'end') 596 | J6degPerStepEntryField.insert(0,str(J6degPerStep)) 597 | J6calAng = float(J6calAngleEntryField.get()) 598 | J6curStep = int((J6calAng-J6angLimNeg) / J6degPerStep) 599 | J6curStepEntryField.delete(0, 'end') 600 | J6curStepEntryField.insert(0,str(J6curStep)) 601 | J6curAngEntryField.delete(0, 'end') 602 | J6curAngEntryField.insert(0,str(J6calAng)) 603 | ########### 604 | calibration.insert(END, J6stepLimNegEntryField.get()) 605 | calibration.insert(END, J6stepLimPosEntryField.get()) 606 | calibration.insert(END, J6angLimNegEntryField.get()) 607 | calibration.insert(END, J6angLimPosEntryField.get()) 608 | calibration.insert(END, J6degPerStepEntryField.get()) 609 | calibration.insert(END, J6calAngleEntryField.get()) 610 | calibration.insert(END, J6curStepEntryField.get()) 611 | calibration.insert(END, J6curAngEntryField.get()) 612 | calibration.insert(END, J6jogStepsEntryField.get()) 613 | ########### 614 | calibration.insert(END, comPortEntryField.get()) 615 | ########### 616 | value=calibration.get(0,END) 617 | pickle.dump(value,open("ARbot.cal","wb")) 618 | 619 | def savePosData(): 620 | calibration.delete(0, END) 621 | calibration.insert(END, J1stepLimNegEntryField.get()) 622 | calibration.insert(END, J1stepLimPosEntryField.get()) 623 | calibration.insert(END, J1angLimNegEntryField.get()) 624 | calibration.insert(END, J1angLimPosEntryField.get()) 625 | calibration.insert(END, J1degPerStepEntryField.get()) 626 | calibration.insert(END, J1calAngleEntryField.get()) 627 | calibration.insert(END, J1curStepEntryField.get()) 628 | calibration.insert(END, J1curAngEntryField.get()) 629 | calibration.insert(END, J1jogStepsEntryField.get()) 630 | calibration.insert(END, J2stepLimNegEntryField.get()) 631 | calibration.insert(END, J2stepLimPosEntryField.get()) 632 | calibration.insert(END, J2angLimNegEntryField.get()) 633 | calibration.insert(END, J2angLimPosEntryField.get()) 634 | calibration.insert(END, J2degPerStepEntryField.get()) 635 | calibration.insert(END, J2calAngleEntryField.get()) 636 | calibration.insert(END, J2curStepEntryField.get()) 637 | calibration.insert(END, J2curAngEntryField.get()) 638 | calibration.insert(END, J2jogStepsEntryField.get()) 639 | calibration.insert(END, J3stepLimNegEntryField.get()) 640 | calibration.insert(END, J3stepLimPosEntryField.get()) 641 | calibration.insert(END, J3angLimNegEntryField.get()) 642 | calibration.insert(END, J3angLimPosEntryField.get()) 643 | calibration.insert(END, J3degPerStepEntryField.get()) 644 | calibration.insert(END, J3calAngleEntryField.get()) 645 | calibration.insert(END, J3curStepEntryField.get()) 646 | calibration.insert(END, J3curAngEntryField.get()) 647 | calibration.insert(END, J3jogStepsEntryField.get()) 648 | calibration.insert(END, J4stepLimNegEntryField.get()) 649 | calibration.insert(END, J4stepLimPosEntryField.get()) 650 | calibration.insert(END, J4angLimNegEntryField.get()) 651 | calibration.insert(END, J4angLimPosEntryField.get()) 652 | calibration.insert(END, J4degPerStepEntryField.get()) 653 | calibration.insert(END, J4calAngleEntryField.get()) 654 | calibration.insert(END, J4curStepEntryField.get()) 655 | calibration.insert(END, J4curAngEntryField.get()) 656 | calibration.insert(END, J4jogStepsEntryField.get()) 657 | calibration.insert(END, J5stepLimNegEntryField.get()) 658 | calibration.insert(END, J5stepLimPosEntryField.get()) 659 | calibration.insert(END, J5angLimNegEntryField.get()) 660 | calibration.insert(END, J5angLimPosEntryField.get()) 661 | calibration.insert(END, J5degPerStepEntryField.get()) 662 | calibration.insert(END, J5calAngleEntryField.get()) 663 | calibration.insert(END, J5curStepEntryField.get()) 664 | calibration.insert(END, J5curAngEntryField.get()) 665 | calibration.insert(END, J5jogStepsEntryField.get()) 666 | calibration.insert(END, J6stepLimNegEntryField.get()) 667 | calibration.insert(END, J6stepLimPosEntryField.get()) 668 | calibration.insert(END, J6angLimNegEntryField.get()) 669 | calibration.insert(END, J6angLimPosEntryField.get()) 670 | calibration.insert(END, J6degPerStepEntryField.get()) 671 | calibration.insert(END, J6calAngleEntryField.get()) 672 | calibration.insert(END, J6curStepEntryField.get()) 673 | calibration.insert(END, J6curAngEntryField.get()) 674 | calibration.insert(END, J6jogStepsEntryField.get()) 675 | calibration.insert(END, comPortEntryField.get()) 676 | calibration.insert(END, ProgEntryField.get()) 677 | calibration.insert(END, servo0onEntryField.get()) 678 | calibration.insert(END, servo0offEntryField.get()) 679 | calibration.insert(END, servo1onEntryField.get()) 680 | calibration.insert(END, servo1offEntryField.get()) 681 | calibration.insert(END, servo2onEntryField.get()) 682 | calibration.insert(END, servo2offEntryField.get()) 683 | calibration.insert(END, servo3onEntryField.get()) 684 | calibration.insert(END, servo3offEntryField.get()) 685 | ########### 686 | value=calibration.get(0,END) 687 | pickle.dump(value,open("ARbot.cal","wb")) 688 | 689 | 690 | def J1jogNeg(): 691 | Speed = speedEntryField.get() 692 | J1jogSteps = J1jogStepsEntryField.get() 693 | J1curStep = int(J1curStepEntryField.get()) 694 | J1curAng = float(J1curAngEntryField.get()) 695 | if (J1curStep >= int(J1jogSteps)): 696 | ser.write("MJA0"+J1jogSteps+"S"+Speed+"\n") 697 | ser.flushInput() 698 | time.sleep(.1) 699 | ser.read() 700 | J1curStep = J1curStep - int(J1jogSteps) 701 | J1curStepEntryField.delete(0, 'end') 702 | J1curStepEntryField.insert(0,str(J1curStep)) 703 | DegPerStep = float(J1degPerStepEntryField.get()) 704 | J1totAng = DegPerStep * float(J1jogSteps) 705 | J1newAng = J1curAng - J1totAng 706 | J1curAngEntryField.delete(0, 'end') 707 | J1curAngEntryField.insert(0,str(J1newAng)) 708 | savePosData() 709 | 710 | 711 | def J1jogPos(): 712 | Speed = speedEntryField.get() 713 | J1jogSteps = J1jogStepsEntryField.get() 714 | J1curStep = int(J1curStepEntryField.get()) 715 | J1curAng = float(J1curAngEntryField.get()) 716 | J1posLim = int(J1stepLimPosEntryField.get()) 717 | J1stepsRem = J1posLim - int(J1curStep) 718 | if (int(J1jogSteps) <= J1stepsRem): 719 | ser.write("MJA1"+J1jogSteps+"S"+Speed+"\n") 720 | ser.flushInput() 721 | time.sleep(.1) 722 | ser.read() 723 | J1curStep = J1curStep + int(J1jogSteps) 724 | J1curStepEntryField.delete(0, 'end') 725 | J1curStepEntryField.insert(0,str(J1curStep)) 726 | DegPerStep = float(J1degPerStepEntryField.get()) 727 | J1totAng = DegPerStep * float(J1jogSteps) 728 | J1newAng = J1curAng + J1totAng 729 | J1curAngEntryField.delete(0, 'end') 730 | J1curAngEntryField.insert(0,str(J1newAng)) 731 | savePosData() 732 | 733 | def J2jogNeg(): 734 | Speed = speedEntryField.get() 735 | J2jogSteps = J2jogStepsEntryField.get() 736 | J2curStep = int(J2curStepEntryField.get()) 737 | J2curAng = float(J2curAngEntryField.get()) 738 | if (J2curStep >= int(J2jogSteps)): 739 | ser.write("MJB1"+J2jogSteps+"S"+Speed+"\n") 740 | ser.flushInput() 741 | time.sleep(.1) 742 | ser.read() 743 | J2curStep = J2curStep - int(J2jogSteps) 744 | J2curStepEntryField.delete(0, 'end') 745 | J2curStepEntryField.insert(0,str(J2curStep)) 746 | DegPerStep = float(J2degPerStepEntryField.get()) 747 | J2totAng = DegPerStep * float(J2jogSteps) 748 | J2newAng = J2curAng - J2totAng 749 | J2curAngEntryField.delete(0, 'end') 750 | J2curAngEntryField.insert(0,str(J2newAng)) 751 | savePosData() 752 | 753 | 754 | def J2jogPos(): 755 | Speed = speedEntryField.get() 756 | J2jogSteps = J2jogStepsEntryField.get() 757 | J2curStep = int(J2curStepEntryField.get()) 758 | J2curAng = float(J2curAngEntryField.get()) 759 | J2posLim = int(J2stepLimPosEntryField.get()) 760 | J2stepsRem = J2posLim - int(J2curStep) 761 | if (int(J2jogSteps) <= J2stepsRem): 762 | ser.write("MJB0"+J2jogSteps+"S"+Speed+"\n") 763 | ser.flushInput() 764 | time.sleep(.1) 765 | ser.read() 766 | J2curStep = J2curStep +int(J2jogSteps) 767 | J2curStepEntryField.delete(0, 'end') 768 | J2curStepEntryField.insert(0,str(J2curStep)) 769 | DegPerStep = float(J2degPerStepEntryField.get()) 770 | J2totAng = DegPerStep * float(J2jogSteps) 771 | J2newAng = J2curAng +J2totAng 772 | J2curAngEntryField.delete(0, 'end') 773 | J2curAngEntryField.insert(0,str(J2newAng)) 774 | savePosData() 775 | 776 | def J3jogNeg(): 777 | Speed = speedEntryField.get() 778 | J3jogSteps = J3jogStepsEntryField.get() 779 | J3curStep = int(J3curStepEntryField.get()) 780 | J3curAng = float(J3curAngEntryField.get()) 781 | if (J3curStep >= int(J3jogSteps)): 782 | ser.write("MJC1"+J3jogSteps+"S"+Speed+"\n") 783 | ser.flushInput() 784 | time.sleep(.1) 785 | ser.read() 786 | J3curStep = J3curStep - int(J3jogSteps) 787 | J3curStepEntryField.delete(0, 'end') 788 | J3curStepEntryField.insert(0,str(J3curStep)) 789 | DegPerStep = float(J3degPerStepEntryField.get()) 790 | J3totAng = DegPerStep * float(J3jogSteps) 791 | J3newAng = J3curAng - J3totAng 792 | J3curAngEntryField.delete(0, 'end') 793 | J3curAngEntryField.insert(0,str(J3newAng)) 794 | savePosData() 795 | 796 | 797 | def J3jogPos(): 798 | Speed = speedEntryField.get() 799 | J3jogSteps = J3jogStepsEntryField.get() 800 | J3curStep = int(J3curStepEntryField.get()) 801 | J3curAng = float(J3curAngEntryField.get()) 802 | J3posLim = int(J3stepLimPosEntryField.get()) 803 | J3stepsRem = J3posLim - int(J3curStep) 804 | if (int(J3jogSteps) <= J3stepsRem): 805 | ser.write("MJC0"+J3jogSteps+"S"+Speed+"\n") 806 | ser.flushInput() 807 | time.sleep(.1) 808 | ser.read() 809 | J3curStep = J3curStep + int(J3jogSteps) 810 | J3curStepEntryField.delete(0, 'end') 811 | J3curStepEntryField.insert(0,str(J3curStep)) 812 | DegPerStep = float(J3degPerStepEntryField.get()) 813 | J3totAng = DegPerStep * float(J3jogSteps) 814 | J3newAng = J3curAng + J3totAng 815 | J3curAngEntryField.delete(0, 'end') 816 | J3curAngEntryField.insert(0,str(J3newAng)) 817 | savePosData() 818 | 819 | 820 | def J4jogNeg(): 821 | Speed = speedEntryField.get() 822 | J4jogSteps = J4jogStepsEntryField.get() 823 | J4curStep = int(J4curStepEntryField.get()) 824 | J4curAng = float(J4curAngEntryField.get()) 825 | if (J4curStep >= int(J4jogSteps)): 826 | ser.write("MJD1"+J4jogSteps+"S"+Speed+"\n") 827 | ser.flushInput() 828 | time.sleep(.1) 829 | ser.read() 830 | J4curStep = J4curStep - int(J4jogSteps) 831 | J4curStepEntryField.delete(0, 'end') 832 | J4curStepEntryField.insert(0,str(J4curStep)) 833 | DegPerStep = float(J4degPerStepEntryField.get()) 834 | J4totAng = DegPerStep * float(J4jogSteps) 835 | J4newAng = J4curAng - J4totAng 836 | J4curAngEntryField.delete(0, 'end') 837 | J4curAngEntryField.insert(0,str(J4newAng)) 838 | savePosData() 839 | 840 | 841 | def J4jogPos(): 842 | Speed = speedEntryField.get() 843 | J4jogSteps = J4jogStepsEntryField.get() 844 | J4curStep = int(J4curStepEntryField.get()) 845 | J4curAng = float(J4curAngEntryField.get()) 846 | J4posLim = int(J4stepLimPosEntryField.get()) 847 | J4stepsRem = J4posLim - int(J4curStep) 848 | if (int(J4jogSteps) <= J4stepsRem): 849 | ser.write("MJD0"+J4jogSteps+"S"+Speed+"\n") 850 | ser.flushInput() 851 | time.sleep(.1) 852 | ser.read() 853 | J4curStep = J4curStep + int(J4jogSteps) 854 | J4curStepEntryField.delete(0, 'end') 855 | J4curStepEntryField.insert(0,str(J4curStep)) 856 | DegPerStep = float(J4degPerStepEntryField.get()) 857 | J4totAng = DegPerStep * float(J4jogSteps) 858 | J4newAng = J4curAng + J4totAng 859 | J4curAngEntryField.delete(0, 'end') 860 | J4curAngEntryField.insert(0,str(J4newAng)) 861 | savePosData() 862 | 863 | def J5jogNeg(): 864 | Speed = speedEntryField.get() 865 | J5jogSteps = J5jogStepsEntryField.get() 866 | J5curStep = int(J5curStepEntryField.get()) 867 | J5curAng = float(J5curAngEntryField.get()) 868 | if (J5curStep >= int(J5jogSteps)): 869 | ser.write("MJE0"+J5jogSteps+"S"+Speed+"\n") 870 | ser.flushInput() 871 | time.sleep(.1) 872 | ser.read() 873 | J5curStep = J5curStep - int(J5jogSteps) 874 | J5curStepEntryField.delete(0, 'end') 875 | J5curStepEntryField.insert(0,str(J5curStep)) 876 | DegPerStep = float(J5degPerStepEntryField.get()) 877 | J5totAng = DegPerStep * float(J5jogSteps) 878 | J5newAng = J5curAng - J5totAng 879 | J5curAngEntryField.delete(0, 'end') 880 | J5curAngEntryField.insert(0,str(J5newAng)) 881 | savePosData() 882 | 883 | 884 | def J5jogPos(): 885 | Speed = speedEntryField.get() 886 | J5jogSteps = J5jogStepsEntryField.get() 887 | J5curStep = int(J5curStepEntryField.get()) 888 | J5curAng = float(J5curAngEntryField.get()) 889 | J5posLim = int(J5stepLimPosEntryField.get()) 890 | J5stepsRem = J5posLim - int(J5curStep) 891 | if (int(J5jogSteps) <= J5stepsRem): 892 | ser.write("MJE1"+J5jogSteps+"S"+Speed+"\n") 893 | ser.flushInput() 894 | time.sleep(.1) 895 | ser.read() 896 | J5curStep = J5curStep + int(J5jogSteps) 897 | J5curStepEntryField.delete(0, 'end') 898 | J5curStepEntryField.insert(0,str(J5curStep)) 899 | DegPerStep = float(J5degPerStepEntryField.get()) 900 | J5totAng = DegPerStep * float(J5jogSteps) 901 | J5newAng = J5curAng + J5totAng 902 | J5curAngEntryField.delete(0, 'end') 903 | J5curAngEntryField.insert(0,str(J5newAng)) 904 | savePosData() 905 | 906 | def J6jogNeg(): 907 | Speed = speedEntryField.get() 908 | J6jogSteps = J6jogStepsEntryField.get() 909 | J6curStep = int(J6curStepEntryField.get()) 910 | J6curAng = float(J6curAngEntryField.get()) 911 | if (J6curStep >= int(J6jogSteps)): 912 | ser.write("MJF1"+J6jogSteps+"S"+Speed+"\n") 913 | ser.flushInput() 914 | time.sleep(.1) 915 | ser.read() 916 | J6curStep = J6curStep - int(J6jogSteps) 917 | J6curStepEntryField.delete(0, 'end') 918 | J6curStepEntryField.insert(0,str(J6curStep)) 919 | DegPerStep = float(J6degPerStepEntryField.get()) 920 | J6totAng = DegPerStep * float(J6jogSteps) 921 | J6newAng = J6curAng - J6totAng 922 | J6curAngEntryField.delete(0, 'end') 923 | J6curAngEntryField.insert(0,str(J6newAng)) 924 | savePosData() 925 | 926 | 927 | def J6jogPos(): 928 | Speed = speedEntryField.get() 929 | J6jogSteps = J6jogStepsEntryField.get() 930 | J6curStep = int(J6curStepEntryField.get()) 931 | J6curAng = float(J6curAngEntryField.get()) 932 | J6posLim = int(J6stepLimPosEntryField.get()) 933 | J6stepsRem = J6posLim - int(J6curStep) 934 | if (int(J6jogSteps) <= J6stepsRem): 935 | ser.write("MJF0"+J6jogSteps+"S"+Speed+"\n") 936 | ser.flushInput() 937 | time.sleep(.1) 938 | ser.read() 939 | J6curStep = J6curStep + int(J6jogSteps) 940 | J6curStepEntryField.delete(0, 'end') 941 | J6curStepEntryField.insert(0,str(J6curStep)) 942 | DegPerStep = float(J6degPerStepEntryField.get()) 943 | J6totAng = DegPerStep * float(J6jogSteps) 944 | J6newAng = J6curAng + J6totAng 945 | J6curAngEntryField.delete(0, 'end') 946 | J6curAngEntryField.insert(0,str(J6newAng)) 947 | savePosData() 948 | 949 | 950 | def teachInsertEnd(): 951 | Speed = speedEntryField.get() 952 | J1curAng = J1curAngEntryField.get() 953 | J2curAng = J2curAngEntryField.get() 954 | J3curAng = J3curAngEntryField.get() 955 | J4curAng = J4curAngEntryField.get() 956 | J5curAng = J5curAngEntryField.get() 957 | J6curAng = J6curAngEntryField.get() 958 | newPos = "Move J J1-"+J1curAng+" J2-"+J2curAng+" J3-"+J3curAng+" J4-"+J4curAng+" J5-"+J5curAng+" J6-"+J6curAng+" Speed-"+Speed 959 | root.progView.insert(END, newPos) 960 | value=root.progView.get(0,END) 961 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 962 | 963 | def teachInsertBelSelected(): 964 | selRow = root.progView.curselection()[0] 965 | selRow += 1 966 | Speed = speedEntryField.get() 967 | J1curAng = J1curAngEntryField.get() 968 | J2curAng = J2curAngEntryField.get() 969 | J3curAng = J3curAngEntryField.get() 970 | J4curAng = J4curAngEntryField.get() 971 | J5curAng = J5curAngEntryField.get() 972 | J6curAng = J6curAngEntryField.get() 973 | newPos = "Move J J1-"+J1curAng+" J2-"+J2curAng+" J3-"+J3curAng+" J4-"+J4curAng+" J5-"+J5curAng+" J6-"+J6curAng+" Speed-"+Speed 974 | root.progView.insert(selRow, newPos) 975 | root.progView.selection_clear(0, END) 976 | root.progView.select_set(selRow) 977 | value=root.progView.get(0,END) 978 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 979 | 980 | def teachReplaceSelected(): 981 | selRow = root.progView.curselection()[0] 982 | Speed = speedEntryField.get() 983 | J1curAng = J1curAngEntryField.get() 984 | J2curAng = J2curAngEntryField.get() 985 | J3curAng = J3curAngEntryField.get() 986 | J4curAng = J4curAngEntryField.get() 987 | J5curAng = J5curAngEntryField.get() 988 | J6curAng = J6curAngEntryField.get() 989 | newPos = "Move J J1-"+J1curAng+" J2-"+J2curAng+" J3-"+J3curAng+" J4-"+J4curAng+" J5-"+J5curAng+" J6-"+J6curAng+" Speed-"+Speed 990 | root.progView.insert(selRow, newPos) 991 | selection = root.progView.curselection() 992 | root.progView.delete(selection[0]) 993 | root.progView.select_set(selRow) 994 | value=root.progView.get(0,END) 995 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 996 | 997 | 998 | def manAdditem(): 999 | selRow = root.progView.curselection()[0] 1000 | selRow += 1 1001 | root.progView.insert(selRow, manEntryField.get()) 1002 | root.progView.selection_clear(0, END) 1003 | root.progView.select_set(selRow) 1004 | value=root.progView.get(0,END) 1005 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1006 | 1007 | 1008 | 1009 | def teachHome(): 1010 | selRow = root.progView.curselection()[0] 1011 | selRow += 5 1012 | header = "### MOVE HOME START ###" 1013 | root.progView.insert(selRow, header) 1014 | J1curAng = float(J1calAngleEntryField.get())+(float(J1degPerStepEntryField.get())*15) 1015 | J2curAng = float(J2calAngleEntryField.get())+(float(J2degPerStepEntryField.get())*60) 1016 | J3curAng = float(J3calAngleEntryField.get())+(float(J3degPerStepEntryField.get())*480) 1017 | J4curAng = float(J4calAngleEntryField.get()) 1018 | J5curAng = float(J5calAngleEntryField.get())-(float(J5degPerStepEntryField.get())*50) 1019 | J6curAng = float(J6calAngleEntryField.get()) 1020 | Speed = speedEntryField.get() 1021 | newPos = "Move J J1-"+str(J1curAng)+" J2-"+str(J2curAng)+" J3-"+str(J3curAng)+" J4-"+str(J4curAng)+" J5-"+str(J5curAng)+" J6-"+str(J6curAng)+" Speed-"+Speed 1022 | root.progView.insert(selRow, newPos) 1023 | ### 1024 | J1curAng = float(J1calAngleEntryField.get())+(float(J1degPerStepEntryField.get())*15) 1025 | J2curAng = float(J2calAngleEntryField.get()) 1026 | J3curAng = float(J3calAngleEntryField.get()) 1027 | J4curAng = float(J4calAngleEntryField.get()) 1028 | J5curAng = float(J5calAngleEntryField.get()) 1029 | J6curAng = float(J6calAngleEntryField.get()) 1030 | Speed = speedEntryField.get() 1031 | newPos = "Move J J1-"+str(J1curAng)+" J2-"+str(J2curAng)+" J3-"+str(J3curAng)+" J4-"+str(J4curAng)+" J5-"+str(J5curAng)+" J6-"+str(J6curAng)+" Speed-"+Speed 1032 | root.progView.insert(selRow, newPos) 1033 | ### 1034 | J1curAng = int(J1calAngleEntryField.get()) 1035 | J2curAng = int(J2calAngleEntryField.get()) 1036 | J3curAng = int(J3calAngleEntryField.get()) 1037 | J4curAng = int(J4calAngleEntryField.get()) 1038 | J5curAng = int(J5calAngleEntryField.get()) 1039 | J6curAng = int(J6calAngleEntryField.get()) 1040 | Speed = speedEntryField.get() 1041 | newPos = "Move J J1-"+str(J1curAng)+" J2-"+str(J2curAng)+" J3-"+str(J3curAng)+" J4-"+str(J4curAng)+" J5-"+str(J5curAng)+" J6-"+str(J6curAng)+" Speed-"+Speed 1042 | root.progView.insert(selRow, newPos) 1043 | ### 1044 | footer = "### MOVE HOME END ###" 1045 | root.progView.insert(selRow, footer) 1046 | root.progView.selection_clear(0, END) 1047 | root.progView.select_set(selRow) 1048 | value=root.progView.get(0,END) 1049 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1050 | 1051 | def exitHome(): 1052 | selRow = root.progView.curselection()[0] 1053 | selRow += 5 1054 | header = "### EXIT HOME START ###" 1055 | root.progView.insert(selRow, header) 1056 | J1curAng = int(J1calAngleEntryField.get()) 1057 | J2curAng = int(J2calAngleEntryField.get()) 1058 | J3curAng = int(J3calAngleEntryField.get()) 1059 | J4curAng = int(J4calAngleEntryField.get()) 1060 | J5curAng = int(J5calAngleEntryField.get()) 1061 | J6curAng = int(J6calAngleEntryField.get()) 1062 | Speed = speedEntryField.get() 1063 | newPos = "Move J J1-"+str(J1curAng)+" J2-"+str(J2curAng)+" J3-"+str(J3curAng)+" J4-"+str(J4curAng)+" J5-"+str(J5curAng)+" J6-"+str(J6curAng)+" Speed-"+Speed 1064 | root.progView.insert(selRow, newPos) 1065 | ### 1066 | J1curAng = float(J1calAngleEntryField.get())+(float(J1degPerStepEntryField.get())*15) 1067 | J2curAng = float(J2calAngleEntryField.get()) 1068 | J3curAng = float(J3calAngleEntryField.get()) 1069 | J4curAng = float(J4calAngleEntryField.get()) 1070 | J5curAng = float(J5calAngleEntryField.get()) 1071 | J6curAng = float(J6calAngleEntryField.get()) 1072 | Speed = speedEntryField.get() 1073 | newPos = "Move J J1-"+str(J1curAng)+" J2-"+str(J2curAng)+" J3-"+str(J3curAng)+" J4-"+str(J4curAng)+" J5-"+str(J5curAng)+" J6-"+str(J6curAng)+" Speed-"+Speed 1074 | root.progView.insert(selRow, newPos) 1075 | ### 1076 | J1curAng = float(J1calAngleEntryField.get())+(float(J1degPerStepEntryField.get())*15) 1077 | J2curAng = float(J2calAngleEntryField.get())+(float(J2degPerStepEntryField.get())*60) 1078 | J3curAng = float(J3calAngleEntryField.get())+(float(J3degPerStepEntryField.get())*480) 1079 | J4curAng = float(J4calAngleEntryField.get()) 1080 | J5curAng = float(J5calAngleEntryField.get())-(float(J5degPerStepEntryField.get())*50) 1081 | J6curAng = float(J6calAngleEntryField.get()) 1082 | Speed = speedEntryField.get() 1083 | newPos = "Move J J1-"+str(J1curAng)+" J2-"+str(J2curAng)+" J3-"+str(J3curAng)+" J4-"+str(J4curAng)+" J5-"+str(J5curAng)+" J6-"+str(J6curAng)+" Speed-"+Speed 1084 | root.progView.insert(selRow, newPos) 1085 | ### 1086 | footer = "### EXIT HOME END ###" 1087 | root.progView.insert(selRow, footer) 1088 | root.progView.selection_clear(0, END) 1089 | root.progView.select_set(selRow) 1090 | value=root.progView.get(0,END) 1091 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1092 | 1093 | 1094 | 1095 | def waitTime(): 1096 | selRow = root.progView.curselection()[0] 1097 | selRow += 1 1098 | seconds = waitTimeEntryField.get() 1099 | newTime = "Wait T - wait time - Seconds-"+seconds 1100 | root.progView.insert(selRow, newTime) 1101 | root.progView.selection_clear(0, END) 1102 | root.progView.select_set(selRow) 1103 | value=root.progView.get(0,END) 1104 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1105 | 1106 | 1107 | def waitInputOn(): 1108 | selRow = root.progView.curselection()[0] 1109 | selRow += 1 1110 | input = waitInputEntryField.get() 1111 | newInput = "Wait I - wait input ON - Input-"+input 1112 | root.progView.insert(selRow, newInput) 1113 | root.progView.selection_clear(0, END) 1114 | root.progView.select_set(selRow) 1115 | value=root.progView.get(0,END) 1116 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1117 | 1118 | def waitInputOff(): 1119 | selRow = root.progView.curselection()[0] 1120 | selRow += 1 1121 | input = waitInputOffEntryField.get() 1122 | newInput = "Wait Off - wait input OFF - Input-"+input 1123 | root.progView.insert(selRow, newInput) 1124 | root.progView.selection_clear(0, END) 1125 | root.progView.select_set(selRow) 1126 | value=root.progView.get(0,END) 1127 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1128 | 1129 | def setOutputOn(): 1130 | selRow = root.progView.curselection()[0] 1131 | selRow += 1 1132 | output = outputOnEntryField.get() 1133 | newOutput = "Out On - set output ON - Output-"+output 1134 | root.progView.insert(selRow, newOutput) 1135 | root.progView.selection_clear(0, END) 1136 | root.progView.select_set(selRow) 1137 | value=root.progView.get(0,END) 1138 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1139 | 1140 | def setOutputOff(): 1141 | selRow = root.progView.curselection()[0] 1142 | selRow += 1 1143 | output = outputOffEntryField.get() 1144 | newOutput = "Out Off - set output OFF - Output-"+output 1145 | root.progView.insert(selRow, newOutput) 1146 | root.progView.selection_clear(0, END) 1147 | root.progView.select_set(selRow) 1148 | value=root.progView.get(0,END) 1149 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1150 | 1151 | def tabNumber(): 1152 | selRow = root.progView.curselection()[0] 1153 | selRow += 1 1154 | tabNum = tabNumEntryField.get() 1155 | tabins = "Tab Number "+tabNum 1156 | root.progView.insert(selRow, tabins) 1157 | value=root.progView.get(0,END) 1158 | root.progView.selection_clear(0, END) 1159 | root.progView.select_set(selRow) 1160 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1161 | tabNumEntryField.delete(0, 'end') 1162 | 1163 | def jumpTab(): 1164 | selRow = root.progView.curselection()[0] 1165 | selRow += 1 1166 | tabNum = jumpTabEntryField.get() 1167 | tabjmp = "Jump Tab-"+tabNum 1168 | root.progView.insert(selRow, tabjmp) 1169 | value=root.progView.get(0,END) 1170 | root.progView.selection_clear(0, END) 1171 | root.progView.select_set(selRow) 1172 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1173 | tabNumEntryField.delete(0, 'end') 1174 | 1175 | def IfOnjumpTab(): 1176 | selRow = root.progView.curselection()[0] 1177 | selRow += 1 1178 | inpNum = IfOnjumpInputTabEntryField.get() 1179 | tabNum = IfOnjumpNumberTabEntryField.get() 1180 | tabjmp = "If On Jump - Input-"+inpNum+" Jump to Tab-"+tabNum 1181 | root.progView.insert(selRow, tabjmp) 1182 | value=root.progView.get(0,END) 1183 | root.progView.selection_clear(0, END) 1184 | root.progView.select_set(selRow) 1185 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1186 | tabNumEntryField.delete(0, 'end') 1187 | 1188 | def IfOffjumpTab(): 1189 | selRow = root.progView.curselection()[0] 1190 | selRow += 1 1191 | inpNum = IfOffjumpInputTabEntryField.get() 1192 | tabNum = IfOffjumpNumberTabEntryField.get() 1193 | tabjmp = "If Off Jump - Input-"+inpNum+" Jump to Tab-"+tabNum 1194 | root.progView.insert(selRow, tabjmp) 1195 | value=root.progView.get(0,END) 1196 | root.progView.selection_clear(0, END) 1197 | root.progView.select_set(selRow) 1198 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1199 | tabNumEntryField.delete(0, 'end') 1200 | 1201 | 1202 | def Servo(): 1203 | selRow = root.progView.curselection()[0] 1204 | selRow += 1 1205 | servoNum = servoNumEntryField.get() 1206 | servoPos = servoPosEntryField.get() 1207 | servoins = "Servo number "+servoNum+" to position: "+servoPos 1208 | root.progView.insert(selRow, servoins) 1209 | root.progView.selection_clear(0, END) 1210 | root.progView.select_set(selRow) 1211 | value=root.progView.get(0,END) 1212 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1213 | 1214 | def loadProg(): 1215 | progframe=Frame(root) 1216 | progframe.place(x=20,y=172) 1217 | #progframe.pack(side=RIGHT, fill=Y) 1218 | scrollbar = Scrollbar(progframe) 1219 | scrollbar.pack(side=RIGHT, fill=Y) 1220 | root.progView = Listbox(progframe,width=48,height=31, yscrollcommand=scrollbar.set) 1221 | root.progView.bind('<>', progViewselect) 1222 | try: 1223 | Prog = pickle.load(open(ProgEntryField.get(),"rb")) 1224 | except: 1225 | try: 1226 | Prog = ['##BEGINNING OF PROGRAM##','Tab Number 1'] 1227 | pickle.dump(Prog,open(ProgEntryField.get(),"wb")) 1228 | except: 1229 | Prog = ['##BEGINNING OF PROGRAM##','Tab Number 1'] 1230 | pickle.dump(Prog,open("new","wb")) 1231 | ProgEntryField.insert(0,"new") 1232 | time.sleep(.1) 1233 | for item in Prog: 1234 | root.progView.insert(END,item) 1235 | root.progView.pack() 1236 | scrollbar.config(command=root.progView.yview) 1237 | savePosData() 1238 | 1239 | def insertCallProg(): 1240 | selRow = root.progView.curselection()[0] 1241 | selRow += 1 1242 | newProg = changeProgEntryField.get() 1243 | changeProg = "Call Program - "+newProg 1244 | root.progView.insert(selRow, changeProg) 1245 | root.progView.selection_clear(0, END) 1246 | root.progView.select_set(selRow) 1247 | value=root.progView.get(0,END) 1248 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1249 | 1250 | def insertReturn(): 1251 | selRow = root.progView.curselection()[0] 1252 | selRow += 1 1253 | value = "Return" 1254 | root.progView.insert(selRow, value) 1255 | root.progView.selection_clear(0, END) 1256 | root.progView.select_set(selRow) 1257 | value=root.progView.get(0,END) 1258 | pickle.dump(value,open(ProgEntryField.get(),"wb")) 1259 | 1260 | 1261 | def progViewselect(e): 1262 | selRow = root.progView.curselection()[0] 1263 | curRowEntryField.delete(0, 'end') 1264 | curRowEntryField.insert(0,selRow) 1265 | 1266 | 1267 | def Servo0on(): 1268 | savePosData() 1269 | servoPos = servo0onEntryField.get() 1270 | command = "SV0P"+servoPos 1271 | ser.write(command +"\n") 1272 | ser.flushInput() 1273 | time.sleep(.1) 1274 | ser.read() 1275 | 1276 | 1277 | def Servo0off(): 1278 | savePosData() 1279 | servoPos = servo0offEntryField.get() 1280 | command = "SV0P"+servoPos 1281 | ser.write(command +"\n") 1282 | ser.flushInput() 1283 | time.sleep(.1) 1284 | ser.read() 1285 | 1286 | 1287 | def Servo1on(): 1288 | savePosData() 1289 | servoPos = servo1onEntryField.get() 1290 | command = "SV1P"+servoPos 1291 | ser.write(command +"\n") 1292 | ser.flushInput() 1293 | time.sleep(.1) 1294 | ser.read() 1295 | 1296 | 1297 | def Servo1off(): 1298 | savePosData() 1299 | servoPos = servo1offEntryField.get() 1300 | command = "SV1P"+servoPos 1301 | ser.write(command +"\n") 1302 | ser.flushInput() 1303 | time.sleep(.1) 1304 | ser.read() 1305 | 1306 | 1307 | def Servo2on(): 1308 | savePosData() 1309 | servoPos = servo2onEntryField.get() 1310 | command = "SV2P"+servoPos 1311 | ser.write(command +"\n") 1312 | ser.flushInput() 1313 | time.sleep(.1) 1314 | ser.read() 1315 | 1316 | 1317 | def Servo2off(): 1318 | savePosData() 1319 | servoPos = servo2offEntryField.get() 1320 | command = "SV2P"+servoPos 1321 | ser.write(command +"\n") 1322 | ser.flushInput() 1323 | time.sleep(.1) 1324 | ser.read() 1325 | 1326 | 1327 | def Servo3on(): 1328 | savePosData() 1329 | servoPos = servo3onEntryField.get() 1330 | command = "SV3P"+servoPos 1331 | ser.write(command +"\n") 1332 | ser.flushInput() 1333 | time.sleep(.1) 1334 | ser.read() 1335 | 1336 | 1337 | def Servo3off(): 1338 | savePosData() 1339 | servoPos = servo3offEntryField.get() 1340 | command = "SV3P"+servoPos 1341 | ser.write(command +"\n") 1342 | ser.flushInput() 1343 | time.sleep(.1) 1344 | ser.read() 1345 | 1346 | 1347 | ###LABELS################################################################# 1348 | ########################################################################## 1349 | 1350 | curRowLab = Label(root, text = "Current Row = ") 1351 | curRowLab.place(x=200, y=150) 1352 | 1353 | 1354 | runStatusLab = Label(root, text = "PROGRAM STOPPED", bg = "red") 1355 | runStatusLab.place(x=20, y=150) 1356 | 1357 | inoutavailLab = Label(root, text = "INPUTS 22-37 / OUTPUTS 38-53 / SERVOS A0-A7") 1358 | inoutavailLab.place(x=10, y=675) 1359 | 1360 | manEntLab = Label(root, text = "Manual Program Entry") 1361 | manEntLab.place(x=665, y=643) 1362 | 1363 | ifOnLab = Label(root,font=("Arial", 6), text = "Input Tab") 1364 | ifOnLab.place(x=892, y=428) 1365 | 1366 | ifOffLab = Label(root,font=("Arial", 6), text = "Input Tab") 1367 | ifOffLab.place(x=892, y=468) 1368 | 1369 | servoLab = Label(root,font=("Arial", 6), text = "Number Position") 1370 | servoLab.place(x=892, y=508) 1371 | 1372 | StepLimLab = Label(root,fg = "dark blue", text = "Step Limits (-,+)") 1373 | StepLimLab.place(x=340, y=58) 1374 | 1375 | AngLimLab = Label(root,fg = "dark blue", text = "Angle Limits (-,+)") 1376 | AngLimLab.place(x=340, y=83) 1377 | 1378 | ComPortLab = Label(root, text = "COM PORT:") 1379 | ComPortLab.place(x=10, y=10) 1380 | 1381 | ProgLab = Label(root, text = "Program:") 1382 | ProgLab.place(x=10, y=45) 1383 | 1384 | speedLab = Label(root, text = "Robot Speed (%)") 1385 | speedLab.place(x=375, y=320) 1386 | 1387 | 1388 | J1Lab = Label(root, font=("Arial", 22), text = "J1") 1389 | J1Lab.place(x=460, y=20) 1390 | 1391 | J2Lab = Label(root, font=("Arial", 22), text = "J2") 1392 | J2Lab.place(x=550, y=20) 1393 | 1394 | J3Lab = Label(root, font=("Arial", 22), text = "J3") 1395 | J3Lab.place(x=640, y=20) 1396 | 1397 | J4Lab = Label(root, font=("Arial", 22), text = "J4") 1398 | J4Lab.place(x=730, y=20) 1399 | 1400 | J5Lab = Label(root, font=("Arial", 22), text = "J5") 1401 | J5Lab.place(x=820, y=20) 1402 | 1403 | J6Lab = Label(root, font=("Arial", 22), text = "J6") 1404 | J6Lab.place(x=910, y=20) 1405 | 1406 | J1degPerStepLab = Label(root, text = "Degrees per Step") 1407 | J1degPerStepLab.place(x=340, y=108) 1408 | 1409 | J1calAngLab = Label(root,fg = "dark blue", text = "Calibration Angle") 1410 | J1calAngLab.place(x=340, y=133) 1411 | 1412 | J1curStepLab = Label(root, text = "Current Step") 1413 | J1curStepLab.place(x=340, y=158) 1414 | 1415 | J1curAngLab = Label(root, text = "Current Angle") 1416 | J1curAngLab.place(x=340, y=183) 1417 | 1418 | J1jogStepsLab = Label(root,fg = "dark blue", text = "Steps to Jog") 1419 | J1jogStepsLab.place(x=340, y=208) 1420 | 1421 | J1jogRobotLab = Label(root, text = "JOG ROBOT") 1422 | J1jogRobotLab.place(x=340, y=250) 1423 | 1424 | waitTequalsLab = Label(root, text = "=") 1425 | waitTequalsLab.place(x=655, y=360) 1426 | 1427 | waitIequalsLab = Label(root, text = "=") 1428 | waitIequalsLab.place(x=655, y=400) 1429 | 1430 | waitIoffequalsLab = Label(root, text = "=") 1431 | waitIoffequalsLab.place(x=655, y=440) 1432 | 1433 | outputOnequalsLab = Label(root, text = "=") 1434 | outputOnequalsLab.place(x=655, y=480) 1435 | 1436 | outputOffequalsLab = Label(root, text = "=") 1437 | outputOffequalsLab.place(x=655, y=520) 1438 | 1439 | tabequalsLab = Label(root, text = "=") 1440 | tabequalsLab.place(x=875, y=360) 1441 | 1442 | jumpequalsLab = Label(root, text = "=") 1443 | jumpequalsLab.place(x=875, y=400) 1444 | 1445 | jumpIfOnequalsLab = Label(root, text = "=") 1446 | jumpIfOnequalsLab.place(x=875, y=440) 1447 | 1448 | jumpIfOffequalsLab = Label(root, text = "=") 1449 | jumpIfOffequalsLab.place(x=875, y=480) 1450 | 1451 | servoequalsLab = Label(root, text = "=") 1452 | servoequalsLab.place(x=875, y=520) 1453 | 1454 | changeProgequalsLab = Label(root, text = "=") 1455 | changeProgequalsLab.place(x=875, y=560) 1456 | 1457 | servo0onequalsLab = Label(root, text = "=") 1458 | servo0onequalsLab.place(x=395, y=575) 1459 | 1460 | servo0offequalsLab = Label(root, text = "=") 1461 | servo0offequalsLab.place(x=395, y=605) 1462 | 1463 | servo1onequalsLab = Label(root, text = "=") 1464 | servo1onequalsLab.place(x=395, y=635) 1465 | 1466 | servo1offequalsLab = Label(root, text = "=") 1467 | servo1offequalsLab.place(x=395, y=665) 1468 | 1469 | servo2onequalsLab = Label(root, text = "=") 1470 | servo2onequalsLab.place(x=535, y=575) 1471 | 1472 | servo2offequalsLab = Label(root, text = "=") 1473 | servo2offequalsLab.place(x=535, y=605) 1474 | 1475 | servo3onequalsLab = Label(root, text = "=") 1476 | servo3onequalsLab.place(x=535, y=635) 1477 | 1478 | servo3offequalsLab = Label(root, text = "=") 1479 | servo3offequalsLab.place(x=535, y=665) 1480 | 1481 | servoManLab = Label(root, text = "Manual Servo toggle buttons") 1482 | servoManLab.place(x=340, y=555) 1483 | 1484 | 1485 | 1486 | ###BUTTONS################################################################ 1487 | ########################################################################## 1488 | 1489 | servo0onBut = Button(root, text="Servo 0", height=1, width=6, command = Servo0on) 1490 | servo0onBut.place(x=340, y=575) 1491 | 1492 | servo0offBut = Button(root, text="Servo 0", height=1, width=6, command = Servo0off) 1493 | servo0offBut.place(x=340, y=605) 1494 | 1495 | servo1onBut = Button(root, text="Servo 1", height=1, width=6, command = Servo1on) 1496 | servo1onBut.place(x=340, y=635) 1497 | 1498 | servo1offBut = Button(root, text="Servo 1", height=1, width=6, command = Servo1off) 1499 | servo1offBut.place(x=340, y=665) 1500 | 1501 | servo2onBut = Button(root, text="Servo 2", height=1, width=6, command = Servo2on) 1502 | servo2onBut.place(x=480, y=575) 1503 | 1504 | servo2offBut = Button(root, text="Servo 2", height=1, width=6, command = Servo2off) 1505 | servo2offBut.place(x=480, y=605) 1506 | 1507 | servo3onBut = Button(root, text="Servo 3", height=1, width=6, command = Servo3on) 1508 | servo3onBut.place(x=480, y=635) 1509 | 1510 | servo4offBut = Button(root, text="Servo 3", height=1, width=6, command = Servo3off) 1511 | servo4offBut.place(x=480, y=665) 1512 | 1513 | manEntBut = Button(root, text="Enter", height=1, width=10, command = manAdditem) 1514 | manEntBut.place(x=920, y=654) 1515 | 1516 | #teachNewBut = Button(root, text="Teach - Insert Last", height=1, width=20, command = teachInsertEnd) 1517 | #teachNewBut.place(x=340, y=360) 1518 | 1519 | teachInsBut = Button(root, text="Teach New Position", height=1, width=20, command = teachInsertBelSelected) 1520 | teachInsBut.place(x=340, y=360) 1521 | 1522 | teachReplaceBut = Button(root, text="Teach Replace Selected", height=1, width=20, command = teachReplaceSelected) 1523 | teachReplaceBut.place(x=340, y=400) 1524 | 1525 | teachHomeBut = Button(root, text="Move Home - calibrate", height=1, width=20, command = teachHome) 1526 | teachHomeBut.place(x=340, y=440) 1527 | 1528 | exitHomeBut = Button(root, text="Exit Home", height=1, width=20, command = exitHome) 1529 | exitHomeBut.place(x=340, y=480) 1530 | 1531 | waitTimeBut = Button(root, text="Wait Time (seconds)", height=1, width=20, command = waitTime) 1532 | waitTimeBut.place(x=500, y=360) 1533 | 1534 | waitInputOnBut = Button(root, text="Wait Input ON", height=1, width=20, command = waitInputOn) 1535 | waitInputOnBut.place(x=500, y=400) 1536 | 1537 | waitInputOffBut = Button(root, text="Wait Input OFF", height=1, width=20, command = waitInputOff) 1538 | waitInputOffBut.place(x=500, y=440) 1539 | 1540 | setOutputOnBut = Button(root, text="Set Output On", height=1, width=20, command = setOutputOn) 1541 | setOutputOnBut.place(x=500, y=480) 1542 | 1543 | setOutputOffBut = Button(root, text="Set Output OFF", height=1, width=20, command = setOutputOff) 1544 | setOutputOffBut.place(x=500, y=520) 1545 | 1546 | tabNumBut = Button(root, text="Create Tab Number", height=1, width=20, command = tabNumber) 1547 | tabNumBut.place(x=720, y=360) 1548 | 1549 | jumpTabBut = Button(root, text="Jump to Tab", height=1, width=20, command = jumpTab) 1550 | jumpTabBut.place(x=720, y=400) 1551 | 1552 | IfOnjumpTabBut = Button(root, text="If On Jump", height=1, width=20, command = IfOnjumpTab) 1553 | IfOnjumpTabBut.place(x=720, y=440) 1554 | 1555 | IfOffjumpTabBut = Button(root, text="If Off Jump", height=1, width=20, command = IfOffjumpTab) 1556 | IfOffjumpTabBut.place(x=720, y=480) 1557 | 1558 | servoBut = Button(root, text="Servo", height=1, width=20, command = Servo) 1559 | servoBut.place(x=720, y=520) 1560 | 1561 | callBut = Button(root, text="Call Program", height=1, width=20, command = insertCallProg) 1562 | callBut.place(x=720, y=560) 1563 | 1564 | returnBut = Button(root, text="Return", height=1, width=20, command = insertReturn) 1565 | returnBut.place(x=720, y=600) 1566 | 1567 | comPortBut = Button(root, text="Set Com", height=0, width=7, command = setCom) 1568 | comPortBut.place(x=103, y=7) 1569 | 1570 | ProgBut = Button(root, text="Load Program", height=0, width=12, command = loadProg) 1571 | ProgBut.place(x=202, y=42) 1572 | 1573 | 1574 | calibrateBut = Button(root, text="Calibrate Robot", height=1, width=12, command = calRobot) 1575 | calibrateBut.place(x=910, y=300) 1576 | 1577 | deleteBut = Button(root, text="Delete", height=1, width=20, command = deleteitem) 1578 | deleteBut.place(x=340, y=520) 1579 | 1580 | runProgBut = Button(root, height=60, width=60, command = runProg) 1581 | playPhoto=PhotoImage(file="play-icon.gif") 1582 | runProgBut.config(image=playPhoto,width="60",height="60") 1583 | runProgBut.place(x=20, y=80) 1584 | 1585 | stopProgBut = Button(root, height=60, width=60, command = stopProg) 1586 | stopPhoto=PhotoImage(file="stop-icon.gif") 1587 | stopProgBut.config(image=stopPhoto,width="60",height="60") 1588 | stopProgBut.place(x=200, y=80) 1589 | 1590 | fwdBut = Button(root,text="FWD", height=3, width=4, command = stepFwd) 1591 | fwdBut.place(x=100, y=80) 1592 | 1593 | revBut = Button(root,text="REV", height=3, width=4, command = stepRev) 1594 | revBut.place(x=150, y=80) 1595 | 1596 | J1jogNegBut = Button(root,text="-", height=2, width=3, command = J1jogNeg) 1597 | J1jogNegBut.place(x=442, y=240) 1598 | 1599 | J1jogPosBut = Button(root,text="+", height=2, width=3, command = J1jogPos) 1600 | J1jogPosBut.place(x=480, y=240) 1601 | 1602 | J2jogNegBut = Button(root,text="-", height=2, width=3, command = J2jogNeg) 1603 | J2jogNegBut.place(x=532, y=240) 1604 | 1605 | J2jogPosBut = Button(root,text="+", height=2, width=3, command = J2jogPos) 1606 | J2jogPosBut.place(x=570, y=240) 1607 | 1608 | J3jogNegBut = Button(root,text="-", height=2, width=3, command = J3jogNeg) 1609 | J3jogNegBut.place(x=622, y=240) 1610 | 1611 | J3jogPosBut = Button(root,text="+", height=2, width=3, command = J3jogPos) 1612 | J3jogPosBut.place(x=660, y=240) 1613 | 1614 | J4jogNegBut = Button(root,text="-", height=2, width=3, command = J4jogNeg) 1615 | J4jogNegBut.place(x=712, y=240) 1616 | 1617 | J4jogPosBut = Button(root,text="+", height=2, width=3, command = J4jogPos) 1618 | J4jogPosBut.place(x=750, y=240) 1619 | 1620 | J5jogNegBut = Button(root,text="-", height=2, width=3, command = J5jogNeg) 1621 | J5jogNegBut.place(x=802, y=240) 1622 | 1623 | J5jogPosBut = Button(root,text="+", height=2, width=3, command = J5jogPos) 1624 | J5jogPosBut.place(x=840, y=240) 1625 | 1626 | J6jogNegBut = Button(root,text="-", height=2, width=3, command = J6jogNeg) 1627 | J6jogNegBut.place(x=892, y=240) 1628 | 1629 | J6jogPosBut = Button(root,text="+", height=2, width=3, command = J6jogPos) 1630 | J6jogPosBut.place(x=930, y=240) 1631 | 1632 | 1633 | 1634 | 1635 | 1636 | 1637 | 1638 | 1639 | ####ENTRY FIELDS########################################################## 1640 | ########################################################################## 1641 | 1642 | servo0onEntryField = Entry(root,width=5) 1643 | servo0onEntryField.place(x=412, y=577) 1644 | 1645 | servo0offEntryField = Entry(root,width=5) 1646 | servo0offEntryField.place(x=412, y=607) 1647 | 1648 | servo1onEntryField = Entry(root,width=5) 1649 | servo1onEntryField.place(x=412, y=637) 1650 | 1651 | servo1offEntryField = Entry(root,width=5) 1652 | servo1offEntryField.place(x=412, y=667) 1653 | 1654 | servo2onEntryField = Entry(root,width=5) 1655 | servo2onEntryField.place(x=552, y=577) 1656 | 1657 | servo2offEntryField = Entry(root,width=5) 1658 | servo2offEntryField.place(x=552, y=607) 1659 | 1660 | servo3onEntryField = Entry(root,width=5) 1661 | servo3onEntryField.place(x=552, y=637) 1662 | 1663 | servo3offEntryField = Entry(root,width=5) 1664 | servo3offEntryField.place(x=552, y=667) 1665 | 1666 | curRowEntryField = Entry(root,width=5) 1667 | curRowEntryField.place(x=290, y=150) 1668 | 1669 | manEntryField = Entry(root,width=40) 1670 | manEntryField.place(x=665, y=660) 1671 | 1672 | ProgEntryField = Entry(root,width=20) 1673 | ProgEntryField.place(x=70, y=45) 1674 | 1675 | comPortEntryField = Entry(root,width=2) 1676 | comPortEntryField.place(x=80, y=10) 1677 | 1678 | speedEntryField = Entry(root,width=5) 1679 | speedEntryField.place(x=340, y=320) 1680 | 1681 | waitTimeEntryField = Entry(root,width=5) 1682 | waitTimeEntryField.place(x=672, y=363) 1683 | 1684 | waitInputEntryField = Entry(root,width=5) 1685 | waitInputEntryField.place(x=672, y=403) 1686 | 1687 | waitInputOffEntryField = Entry(root,width=5) 1688 | waitInputOffEntryField.place(x=672, y=443) 1689 | 1690 | outputOnEntryField = Entry(root,width=5) 1691 | outputOnEntryField.place(x=672, y=483) 1692 | 1693 | outputOffEntryField = Entry(root,width=5) 1694 | outputOffEntryField.place(x=672, y=523) 1695 | 1696 | tabNumEntryField = Entry(root,width=5) 1697 | tabNumEntryField.place(x=892, y=363) 1698 | 1699 | jumpTabEntryField = Entry(root,width=5) 1700 | jumpTabEntryField.place(x=892, y=403) 1701 | 1702 | IfOnjumpInputTabEntryField = Entry(root,width=5) 1703 | IfOnjumpInputTabEntryField.place(x=892, y=443) 1704 | 1705 | IfOnjumpNumberTabEntryField = Entry(root,width=5) 1706 | IfOnjumpNumberTabEntryField.place(x=932, y=443) 1707 | 1708 | IfOffjumpInputTabEntryField = Entry(root,width=5) 1709 | IfOffjumpInputTabEntryField.place(x=892, y=483) 1710 | 1711 | IfOffjumpNumberTabEntryField = Entry(root,width=5) 1712 | IfOffjumpNumberTabEntryField.place(x=932, y=483) 1713 | 1714 | servoNumEntryField = Entry(root,width=5) 1715 | servoNumEntryField.place(x=892, y=523) 1716 | 1717 | servoPosEntryField = Entry(root,width=5) 1718 | servoPosEntryField.place(x=932, y=523) 1719 | 1720 | changeProgEntryField = Entry(root,width=12) 1721 | changeProgEntryField.place(x=892, y=563) 1722 | 1723 | 1724 | ### J1 ### 1725 | 1726 | J1stepLimNegEntryField = Entry(root,width=5) 1727 | J1stepLimNegEntryField.place(x=442, y=60) 1728 | 1729 | J1stepLimPosEntryField = Entry(root,width=5) 1730 | J1stepLimPosEntryField.place(x=480, y=60) 1731 | 1732 | J1angLimNegEntryField = Entry(root,width=5) 1733 | J1angLimNegEntryField.place(x=442, y=85) 1734 | 1735 | J1angLimPosEntryField = Entry(root,width=5) 1736 | J1angLimPosEntryField.place(x=480, y=85) 1737 | 1738 | J1degPerStepEntryField = Entry(root,width=5) 1739 | J1degPerStepEntryField.place(x=460, y=110) 1740 | 1741 | J1calAngleEntryField = Entry(root,width=5) 1742 | J1calAngleEntryField.place(x=460, y=135) 1743 | 1744 | J1curStepEntryField = Entry(root,width=5) 1745 | J1curStepEntryField.place(x=460, y=160) 1746 | 1747 | J1curAngEntryField = Entry(root,width=5) 1748 | J1curAngEntryField.place(x=460, y=185) 1749 | 1750 | J1jogStepsEntryField = Entry(root,width=5) 1751 | J1jogStepsEntryField.place(x=460, y=210) 1752 | 1753 | 1754 | ### J2 ### 1755 | 1756 | J2stepLimNegEntryField = Entry(root,width=5) 1757 | J2stepLimNegEntryField.place(x=532, y=60) 1758 | 1759 | J2stepLimPosEntryField = Entry(root,width=5) 1760 | J2stepLimPosEntryField.place(x=570, y=60) 1761 | 1762 | J2angLimNegEntryField = Entry(root,width=5) 1763 | J2angLimNegEntryField.place(x=532, y=85) 1764 | 1765 | J2angLimPosEntryField = Entry(root,width=5) 1766 | J2angLimPosEntryField.place(x=570, y=85) 1767 | 1768 | J2degPerStepEntryField = Entry(root,width=5) 1769 | J2degPerStepEntryField.place(x=550, y=110) 1770 | 1771 | J2calAngleEntryField = Entry(root,width=5) 1772 | J2calAngleEntryField.place(x=550, y=135) 1773 | 1774 | J2curStepEntryField = Entry(root,width=5) 1775 | J2curStepEntryField.place(x=550, y=160) 1776 | 1777 | J2curAngEntryField = Entry(root,width=5) 1778 | J2curAngEntryField.place(x=550, y=185) 1779 | 1780 | J2jogStepsEntryField = Entry(root,width=5) 1781 | J2jogStepsEntryField.place(x=550, y=210) 1782 | 1783 | 1784 | ### J3 ### 1785 | 1786 | J3stepLimNegEntryField = Entry(root,width=5) 1787 | J3stepLimNegEntryField.place(x=622, y=60) 1788 | 1789 | J3stepLimPosEntryField = Entry(root,width=5) 1790 | J3stepLimPosEntryField.place(x=660, y=60) 1791 | 1792 | J3angLimNegEntryField = Entry(root,width=5) 1793 | J3angLimNegEntryField.place(x=622, y=85) 1794 | 1795 | J3angLimPosEntryField = Entry(root,width=5) 1796 | J3angLimPosEntryField.place(x=660, y=85) 1797 | 1798 | J3degPerStepEntryField = Entry(root,width=5) 1799 | J3degPerStepEntryField.place(x=640, y=110) 1800 | 1801 | J3calAngleEntryField = Entry(root,width=5) 1802 | J3calAngleEntryField.place(x=640, y=135) 1803 | 1804 | J3curStepEntryField = Entry(root,width=5) 1805 | J3curStepEntryField.place(x=640, y=160) 1806 | 1807 | J3curAngEntryField = Entry(root,width=5) 1808 | J3curAngEntryField.place(x=640, y=185) 1809 | 1810 | J3jogStepsEntryField = Entry(root,width=5) 1811 | J3jogStepsEntryField.place(x=640, y=210) 1812 | 1813 | 1814 | ### J4 ### 1815 | 1816 | J4stepLimNegEntryField = Entry(root,width=5) 1817 | J4stepLimNegEntryField.place(x=712, y=60) 1818 | 1819 | J4stepLimPosEntryField = Entry(root,width=5) 1820 | J4stepLimPosEntryField.place(x=750, y=60) 1821 | 1822 | J4angLimNegEntryField = Entry(root,width=5) 1823 | J4angLimNegEntryField.place(x=712, y=85) 1824 | 1825 | J4angLimPosEntryField = Entry(root,width=5) 1826 | J4angLimPosEntryField.place(x=750, y=85) 1827 | 1828 | J4degPerStepEntryField = Entry(root,width=5) 1829 | J4degPerStepEntryField.place(x=730, y=110) 1830 | 1831 | J4calAngleEntryField = Entry(root,width=5) 1832 | J4calAngleEntryField.place(x=730, y=135) 1833 | 1834 | J4curStepEntryField = Entry(root,width=5) 1835 | J4curStepEntryField.place(x=730, y=160) 1836 | 1837 | J4curAngEntryField = Entry(root,width=5) 1838 | J4curAngEntryField.place(x=730, y=185) 1839 | 1840 | J4jogStepsEntryField = Entry(root,width=5) 1841 | J4jogStepsEntryField.place(x=730, y=210) 1842 | 1843 | 1844 | ### J5 ### 1845 | 1846 | J5stepLimNegEntryField = Entry(root,width=5) 1847 | J5stepLimNegEntryField.place(x=802, y=60) 1848 | 1849 | J5stepLimPosEntryField = Entry(root,width=5) 1850 | J5stepLimPosEntryField.place(x=840, y=60) 1851 | 1852 | J5angLimNegEntryField = Entry(root,width=5) 1853 | J5angLimNegEntryField.place(x=802, y=85) 1854 | 1855 | J5angLimPosEntryField = Entry(root,width=5) 1856 | J5angLimPosEntryField.place(x=840, y=85) 1857 | 1858 | J5degPerStepEntryField = Entry(root,width=5) 1859 | J5degPerStepEntryField.place(x=820, y=110) 1860 | 1861 | J5calAngleEntryField = Entry(root,width=5) 1862 | J5calAngleEntryField.place(x=820, y=135) 1863 | 1864 | J5curStepEntryField = Entry(root,width=5) 1865 | J5curStepEntryField.place(x=820, y=160) 1866 | 1867 | J5curAngEntryField = Entry(root,width=5) 1868 | J5curAngEntryField.place(x=820, y=185) 1869 | 1870 | J5jogStepsEntryField = Entry(root,width=5) 1871 | J5jogStepsEntryField.place(x=820, y=210) 1872 | 1873 | 1874 | ### J6 ### 1875 | 1876 | J6stepLimNegEntryField = Entry(root,width=5) 1877 | J6stepLimNegEntryField.place(x=892, y=60) 1878 | 1879 | J6stepLimPosEntryField = Entry(root,width=5) 1880 | J6stepLimPosEntryField.place(x=930, y=60) 1881 | 1882 | J6angLimNegEntryField = Entry(root,width=5) 1883 | J6angLimNegEntryField.place(x=892, y=85) 1884 | 1885 | J6angLimPosEntryField = Entry(root,width=5) 1886 | J6angLimPosEntryField.place(x=930, y=85) 1887 | 1888 | J6degPerStepEntryField = Entry(root,width=5) 1889 | J6degPerStepEntryField.place(x=910, y=110) 1890 | 1891 | J6calAngleEntryField = Entry(root,width=5) 1892 | J6calAngleEntryField.place(x=910, y=135) 1893 | 1894 | J6curStepEntryField = Entry(root,width=5) 1895 | J6curStepEntryField.place(x=910, y=160) 1896 | 1897 | J6curAngEntryField = Entry(root,width=5) 1898 | J6curAngEntryField.place(x=910, y=185) 1899 | 1900 | J6jogStepsEntryField = Entry(root,width=5) 1901 | J6jogStepsEntryField.place(x=910, y=210) 1902 | 1903 | 1904 | ###OPEN CALIBRATION AND PROG FILE AND LOAD LISTS########################## 1905 | ########################################################################## 1906 | 1907 | 1908 | 1909 | 1910 | 1911 | 1912 | 1913 | 1914 | 1915 | 1916 | 1917 | 1918 | ###OPEN CAL FILE AND LOAD LIST########################################### 1919 | ########################################################################## 1920 | 1921 | calibration = Listbox(root,width=20,height=60) 1922 | #calibration.place(x=160,y=170) 1923 | 1924 | try: 1925 | Cal = pickle.load(open("ARbot.cal","rb")) 1926 | except: 1927 | Cal = "0" 1928 | pickle.dump(Cal,open("ARbot.cal","wb")) 1929 | for item in Cal: 1930 | calibration.insert(END,item) 1931 | J1stepLimNeg=calibration.get("0") 1932 | J1stepLimPos=calibration.get("1") 1933 | J1angLimNeg =calibration.get("2") 1934 | J1angLimPos =calibration.get("3") 1935 | J1degPerStep=calibration.get("4") 1936 | J1calAngle =calibration.get("5") 1937 | J1curStep =calibration.get("6") 1938 | J1curAng =calibration.get("7") 1939 | J1jogSteps =calibration.get("8") 1940 | J2stepLimNeg=calibration.get("9") 1941 | J2stepLimPos=calibration.get("10") 1942 | J2angLimNeg =calibration.get("11") 1943 | J2angLimPos =calibration.get("12") 1944 | J2degPerStep=calibration.get("13") 1945 | J2calAngle =calibration.get("14") 1946 | J2curStep =calibration.get("15") 1947 | J2curAng =calibration.get("16") 1948 | J2jogSteps =calibration.get("17") 1949 | J3stepLimNeg=calibration.get("18") 1950 | J3stepLimPos=calibration.get("19") 1951 | J3angLimNeg =calibration.get("20") 1952 | J3angLimPos =calibration.get("21") 1953 | J3degPerStep=calibration.get("22") 1954 | J3calAngle =calibration.get("23") 1955 | J3curStep =calibration.get("24") 1956 | J3curAng =calibration.get("25") 1957 | J3jogSteps =calibration.get("26") 1958 | J4stepLimNeg=calibration.get("27") 1959 | J4stepLimPos=calibration.get("28") 1960 | J4angLimNeg =calibration.get("29") 1961 | J4angLimPos =calibration.get("30") 1962 | J4degPerStep=calibration.get("31") 1963 | J4calAngle =calibration.get("32") 1964 | J4curStep =calibration.get("33") 1965 | J4curAng =calibration.get("34") 1966 | J4jogSteps =calibration.get("35") 1967 | J5stepLimNeg=calibration.get("36") 1968 | J5stepLimPos=calibration.get("37") 1969 | J5angLimNeg =calibration.get("38") 1970 | J5angLimPos =calibration.get("39") 1971 | J5degPerStep=calibration.get("40") 1972 | J5calAngle =calibration.get("41") 1973 | J5curStep =calibration.get("42") 1974 | J5curAng =calibration.get("43") 1975 | J5jogSteps =calibration.get("44") 1976 | J6stepLimNeg=calibration.get("45") 1977 | J6stepLimPos=calibration.get("46") 1978 | J6angLimNeg =calibration.get("47") 1979 | J6angLimPos =calibration.get("48") 1980 | J6degPerStep=calibration.get("49") 1981 | J6calAngle =calibration.get("50") 1982 | J6curStep =calibration.get("51") 1983 | J6curAng =calibration.get("52") 1984 | J6jogSteps =calibration.get("53") 1985 | comPort =calibration.get("54") 1986 | Prog =calibration.get("55") 1987 | Servo0on =calibration.get("56") 1988 | Servo0off =calibration.get("57") 1989 | Servo1on =calibration.get("58") 1990 | Servo1off =calibration.get("59") 1991 | Servo2on =calibration.get("60") 1992 | Servo2off =calibration.get("61") 1993 | Servo3on =calibration.get("62") 1994 | Servo3off =calibration.get("63") 1995 | 1996 | #### 1997 | J1stepLimNegEntryField.insert(0,str(J1stepLimNeg)) 1998 | J1stepLimPosEntryField.insert(0,str(J1stepLimPos)) 1999 | J1angLimNegEntryField.insert(0,str(J1angLimNeg)) 2000 | J1angLimPosEntryField.insert(0,str(J1angLimPos)) 2001 | J1degPerStepEntryField.insert(0,str(J1degPerStep)) 2002 | J1calAngleEntryField.insert(0,str(J1calAngle)) 2003 | J1curStepEntryField.insert(0,str(J1curStep)) 2004 | J1curAngEntryField.insert(0,str(J1curAng)) 2005 | J1jogStepsEntryField.insert(0,str(J1jogSteps)) 2006 | J2stepLimNegEntryField.insert(0,str(J2stepLimNeg)) 2007 | J2stepLimPosEntryField.insert(0,str(J2stepLimPos)) 2008 | J2angLimNegEntryField.insert(0,str(J2angLimNeg)) 2009 | J2angLimPosEntryField.insert(0,str(J2angLimPos)) 2010 | J2degPerStepEntryField.insert(0,str(J2degPerStep)) 2011 | J2calAngleEntryField.insert(0,str(J2calAngle)) 2012 | J2curStepEntryField.insert(0,str(J2curStep)) 2013 | J2curAngEntryField.insert(0,str(J2curAng)) 2014 | J2jogStepsEntryField.insert(0,str(J2jogSteps)) 2015 | J3stepLimNegEntryField.insert(0,str(J3stepLimNeg)) 2016 | J3stepLimPosEntryField.insert(0,str(J3stepLimPos)) 2017 | J3angLimNegEntryField.insert(0,str(J3angLimNeg)) 2018 | J3angLimPosEntryField.insert(0,str(J3angLimPos)) 2019 | J3degPerStepEntryField.insert(0,str(J3degPerStep)) 2020 | J3calAngleEntryField.insert(0,str(J3calAngle)) 2021 | J3curStepEntryField.insert(0,str(J3curStep)) 2022 | J3curAngEntryField.insert(0,str(J3curAng)) 2023 | J3jogStepsEntryField.insert(0,str(J3jogSteps)) 2024 | J4stepLimNegEntryField.insert(0,str(J4stepLimNeg)) 2025 | J4stepLimPosEntryField.insert(0,str(J4stepLimPos)) 2026 | J4angLimNegEntryField.insert(0,str(J4angLimNeg)) 2027 | J4angLimPosEntryField.insert(0,str(J4angLimPos)) 2028 | J4degPerStepEntryField.insert(0,str(J4degPerStep)) 2029 | J4calAngleEntryField.insert(0,str(J4calAngle)) 2030 | J4curStepEntryField.insert(0,str(J4curStep)) 2031 | J4curAngEntryField.insert(0,str(J4curAng)) 2032 | J4jogStepsEntryField.insert(0,str(J4jogSteps)) 2033 | J5stepLimNegEntryField.insert(0,str(J5stepLimNeg)) 2034 | J5stepLimPosEntryField.insert(0,str(J5stepLimPos)) 2035 | J5angLimNegEntryField.insert(0,str(J5angLimNeg)) 2036 | J5angLimPosEntryField.insert(0,str(J5angLimPos)) 2037 | J5degPerStepEntryField.insert(0,str(J5degPerStep)) 2038 | J5calAngleEntryField.insert(0,str(J5calAngle)) 2039 | J5curStepEntryField.insert(0,str(J5curStep)) 2040 | J5curAngEntryField.insert(0,str(J5curAng)) 2041 | J5jogStepsEntryField.insert(0,str(J5jogSteps)) 2042 | J6stepLimNegEntryField.insert(0,str(J6stepLimNeg)) 2043 | J6stepLimPosEntryField.insert(0,str(J6stepLimPos)) 2044 | J6angLimNegEntryField.insert(0,str(J6angLimNeg)) 2045 | J6angLimPosEntryField.insert(0,str(J6angLimPos)) 2046 | J6degPerStepEntryField.insert(0,str(J6degPerStep)) 2047 | J6calAngleEntryField.insert(0,str(J6calAngle)) 2048 | J6curStepEntryField.insert(0,str(J6curStep)) 2049 | J6curAngEntryField.insert(0,str(J6curAng)) 2050 | J6jogStepsEntryField.insert(0,str(J6jogSteps)) 2051 | comPortEntryField.insert(0,str(comPort)) 2052 | speedEntryField.insert(0,"100") 2053 | ProgEntryField.insert(0,(Prog)) 2054 | servo0onEntryField.insert(0,str(Servo0on)) 2055 | servo0offEntryField.insert(0,str(Servo0off)) 2056 | servo1onEntryField.insert(0,str(Servo1on)) 2057 | servo1offEntryField.insert(0,str(Servo1off)) 2058 | servo2onEntryField.insert(0,str(Servo2on)) 2059 | servo2offEntryField.insert(0,str(Servo2off)) 2060 | servo3onEntryField.insert(0,str(Servo3on)) 2061 | servo3offEntryField.insert(0,str(Servo3off)) 2062 | 2063 | try: 2064 | setCom() 2065 | except: 2066 | print "" 2067 | 2068 | loadProg() 2069 | 2070 | root.mainloop() -------------------------------------------------------------------------------- /Software Source Code/new: -------------------------------------------------------------------------------- 1 | (S'##BEGINNING OF PROGRAM##' 2 | p0 3 | S'Tab Number 1' 4 | p1 5 | tp2 6 | . -------------------------------------------------------------------------------- /Software Source Code/play-icon.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/Software Source Code/play-icon.gif -------------------------------------------------------------------------------- /Software Source Code/setup.py: -------------------------------------------------------------------------------- 1 | from distutils.core import setup 2 | import py2exe, sys, os 3 | 4 | sys.argv.append('py2exe') 5 | 6 | setup( 7 | options = {'py2exe': {'optimize': 2}}, 8 | windows = [{'script': "Annin Robot.py","icon_resources": [(1, "ARbot.ico")]}], 9 | zipfile = "shared.lib", 10 | ) -------------------------------------------------------------------------------- /Software Source Code/stop-icon.gif: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/Software Source Code/stop-icon.gif -------------------------------------------------------------------------------- /Step files/Step files.zip: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/Chris-Annin/Annin-Robot-Project/54c48e2f978cbc07ca5a0645e92e802af934036a/Step files/Step files.zip --------------------------------------------------------------------------------