1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033 1034 1035 1036 1037 1038 1039 1040 1041 1042 1043 1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066 1067 | /** Copyright (C) 2012-2022 by Autodesk, Inc. All rights reserved. ABB Rapid post processor configuration. $Revision: 44142 5297e665dc1eda0fa66638f324c5f24fef600622 $ $Date: 2024-08-29 13:28:19 $ FORKID {70730789-F71E-4A49-89E7-B5658ADA62F8} */ /////////////////////////////////////////////////////////////////////////////// // CUSTOM NC COMMANDS - search for 'Machine specific output, modify as needed' // // endEffectorCommandOn - Modify this variable to define the commands to turn ON the end effector, if needed // endEffectorCommandOff - Modify this variable to define the commands to turn OFF the end effector, if needed // // setWeldingParameters() - to define the Arc welding settings: welddata, seamdata and weavedata // /////////////////////////////////////////////////////////////////////////////// description = "ABB Robotics - Rapid" ; vendor = "ABB" ; legal = "Copyright (C) 2012-2022 by Autodesk, Inc." ; certificationLevel = 2; minimumRevision = 45702; longDescription = "Generic ABB Rapid post. Please refer to the User Guide for programming specification and sample. Always validate with Robot Studio before loading any toolpath on your Robot." ; extension = "txt" ; // status file extension var fileExtension = "pgf" ; // program file extension programNameIsInteger = false ; setCodePage( "ascii" ); capabilities = CAPABILITY_MILLING | CAPABILITY_ADDITIVE; tolerance = spatial(0.1, MM); highFeedrate = (unit == IN) ? 100 : 1000; minimumChordLength = spatial(0.25, MM); minimumCircularRadius = spatial(0.01, MM); maximumCircularRadius = spatial(1000, MM); minimumCircularSweep = toRad(0.01); maximumCircularSweep = toRad(180); allowHelicalMoves = true ; allowSpiralMoves = true ; allowedCircularPlanes = 0; properties = { flipToolFrame: { title : "Flip tool frame" , description: "Flip the tool frame (Z- is along the tool axis)." , group : "parameters" , type : "boolean" , value : true , scope : "post" }, firstPointType: { title : "First point move type" , description: "Set if the first point is defined by joint angles (joints values are needed but arm configuration can be ignored) or using cartesian coordinates (robot arm configuration data are required but joints value can be ignored)." , group : "configuration" , type : "enum" , values : [ {title: "Cartesian" , id: "Cartesian" }, {title: "Joints" , id: "Joints" } ], value: "Joints" , scope: "post" }, useSubfolder: { title : "Use subfolder" , description: "Specifies if files should be saved in subfolder or not." , group : "general" , type : "boolean" , value : true , scope : "post" }, useCoolant: { title : "Use coolants" , description: "Specifies if Robot needs Coolant Codes" , group : "general" , type : "boolean" , value : false , scope : "post" }, nameLimitation: { title : "Toolpath name max 30 chars" , description: "Check if each toolpath name has max 30 characters." , group : "general" , type : "boolean" , value : true , scope : "post" }, robotStartJ1: { title : "Robot joint 1" , description: "ABB robot joint value used for the initial position point before MoveL start." , group : "configuration" , type : "number" , value : 0, scope : "post" }, robotStartJ2: { title : "Robot joint 2" , description: "ABB robot joint value used for the initial position point before MoveL start." , group : "configuration" , type : "number" , value : 0, scope : "post" }, robotStartJ3: { title : "Robot joint 3" , description: "ABB robot joint value used for the initial position point before MoveL start." , group : "configuration" , type : "number" , value : 5, scope : "post" }, robotStartJ4: { title : "Robot joint 4" , description: "ABB robot joint value used for the initial position point before MoveL start." , group : "configuration" , type : "number" , value : -70, scope : "post" }, robotStartJ5: { title : "Robot joint 5" , description: "ABB robot joint value used for the initial position point before MoveL start." , group : "configuration" , type : "number" , value : 40, scope : "post" }, robotStartJ6: { title : "Robot joint 6" , description: "ABB robot joint value used for the initial position point before MoveL start." , group : "configuration" , type : "number" , value : 70, scope : "post" }, robotToolData: { title : "Robot tool name (prefix)" , description: "ABB robot tool name prefix to use." , group : "parameters" , type : "string" , value : "tADSK" , scope : "post" }, robotWorkObjectData: { title : "Robot workobject data name (prefix)" , description: "ABB robot work object data prefix to use." , group : "parameters" , type : "string" , value : "wADSK" , scope : "post" }, robotConfiguration: { title : "Robot configuration" , description: "ABB robot arm configuration." , group : "configuration" , type : "string" , value : "0,-1,0,1" , scope : "post" }, robotHeadAngle: { title : "Head angle" , description: "ABB robot head angle around tool axis. X axis is 0 deg." , group : "proc" , type : "number" , value : 30, scope : "post" }, robotZoneSmoothing: { title : "Robot smoothing value (Zone)" , description: "ABB robot path smoothing value (zone)." , group : "parameters" , type : "integer" , value : 1, scope : "post" }, writeDateAndTime: { title : "Write date and time" , description: "Output date and time in the header of the code." , group : "general" , type : "boolean" , value : true , scope : "post" }, endEffectorBehavior: { title : "End-effector state" , description: "Set the end-effector state (including behavior during flat toolpath transitions)." , group : "proc" , type : "enum" , values : [ {title: "OFF" , id: "Off" }, {title: "ON + links ON" , id: "On" }, {title: "ON + links OFF" , id: "OnOff" } ], value: "Off" , scope: "post" }, fffToolData: { title : "Robot tool data" , description: "ABB tool data used for FFF toolpath" , group : "fff" , type : "integer" , value : 1, scope : "post" }, fffBaseData: { title : "Robot base data" , description: "ABB Work Object Coordinates System (WOCS) used for FFF toolpath" , group : "fff" , type : "integer" , value : 1, scope : "post" }, weldProcess: { title : "Welding mode" , description: "Welding Technology Process ON" , group : "proc" , type : "boolean" , value : false , scope : "post" }, weldingSeamdata: { title : "Welding seamdata" , description: "Describes how the seam is to be started and ended (refer to ABB manual for more details)." , group : "weld" , type : "string" , value : "seam1" , scope : "post" }, weldingWelddata: { title : "Welding welddata" , description: "Describes the actual welding phase (refer to ABB manual for more details)." , group : "weld" , type : "string" , value : "weld1" , scope : "post" }, weldingWeavedata: { title : "Welding weavedata" , description: "Describes how any weaving is to be carried out (refer to ABB manual for more details)." , group : "weld" , type : "string" , value : "weave1" , scope : "post" }, weldingWaitTime: { title : "Welding wait time" , description: "Instruction to wait a given amount of time in seconds." , group : "weld" , type : "number" , value : 0.0, scope : "post" } }; groupDefinitions = { proc : {title: "Process" , description: "Process post settings" , order:0}, configuration: {title: "Configuration" , description: "General robot configuration" , order:1}, parameters : {title: "Parameters" , description: "Robot parameters" , order:2}, weld : {title: "Welding Settings" , description: "Welding settings" , collapsed: true , order:3}, fff : {title: "FFF Settings" , description: "FFF settings" , collapsed: true , order:4}, general : {title: "General" , description: "Other post options" , collapsed: true , order:5} }; var singleLineCoolant = false ; // specifies to output multiple coolant codes in one line rather than in separate lines // samples: // {id: COOLANT_THROUGH_TOOL, on: 88, off: 89} // {id: COOLANT_THROUGH_TOOL, on: [8, 88], off: [9, 89]} // {id: COOLANT_THROUGH_TOOL, on: "M88 P3 (myComment)", off: "M89"} var coolants = [ {id:COOLANT_FLOOD}, {id:COOLANT_MIST}, {id:COOLANT_THROUGH_TOOL}, {id:COOLANT_AIR}, {id:COOLANT_AIR_THROUGH_TOOL}, {id:COOLANT_SUCTION}, {id:COOLANT_FLOOD_MIST}, {id:COOLANT_FLOOD_THROUGH_TOOL}, {id:COOLANT_OFF} ]; var xyzFormat = createFormat({decimals:(unit == MM ? 3 : 4), forceDecimal: false }); var abcFormat = createFormat({decimals:3, forceDecimal: false }); var jointFormat = createFormat({decimals:4, forceDecimal: false }); var quatFormat = createFormat({decimals:8, forceDecimal: false }); var feedFormat = createFormat({decimals:0, forceDecimal: false , scale:1.0 / 60.0}); // mm/min -> mm/s var toolFormat = createFormat({decimals:0}); var rpmFormat = createFormat({decimals:0}); var secFormat = createFormat({decimals:3}); // seconds var taperFormat = createFormat({decimals:1, scale:DEG}); var xOutput = createVariable({prefix: "" , force: true }, xyzFormat); var yOutput = createVariable({prefix: "" , force: true }, xyzFormat); var zOutput = createVariable({onchange: function () {retracted = false ;}, prefix: "" , force: true }, xyzFormat); var feedOutput = createVariable({prefix: "v" , force: true }, feedFormat); var sOutput = createVariable({prefix: "" , force: true }, rpmFormat); var integerFormat = createFormat({decimals:0}); // collected state var retracted = false ; // specifies that the tool has been retracted to the safe plane var firstLin = true ; // set during onSection to reset first toolpath point var pendingRadiusCompensation = -1; var currentToolDataName = "" ; var currentWorkObjectDataName = "" ; var endEffectorState = 0; // initial state of the end effector (0 =off) var wasEndEffectorOn = 0; // used to check previous value of endEffectorState var folder; var mainProgram; var programFilename; var subNames = new Array(); var speeddata = new Array(); var toolpathNames = new Array(); // Machine specific output, modify as needed var predefinedspeed = new Array( "v5" , "v10" , "v25" , "v30" , "v40" , "v50" , "v60" , "v80" , "v100" , "v150" , "v200" , "v300" , "v400" , "v500" , "v600" , "v800" , "v1000" ); var permittedCommentChars = " abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789.,=_-+" ; /** Writes the specified block. */ function writeBlock() { writeWords(arguments); } /** Formats a comment. */ function formatComment(text) { return " ! " + filterText(String(text), permittedCommentChars).replace(/[()]/g, "" ); } /** Output a comment. */ function writeComment(text) { writeln(formatComment(text)); } function onOpen() { // Machine requires output only in MM unit = MM; setWordSeparator( "," ); if (getProperty( "endEffectorBehavior" ) == "Off" && getProperty( "weldProcess" )) { error(localize( "In welding mode please activate the prefered end-effector state." )); } // create subfolder if requested folder = FileSystem.getFolderPath(getOutputPath()); if (getProperty( "useSubfolder" )) { folder = FileSystem.getCombinedPath(folder, programName); if (!FileSystem.isFolder(folder)) { FileSystem.makeFolder(folder); } } programFilename = FileSystem.replaceExtension(FileSystem.getFilename(getOutputPath()), fileExtension); redirectToBuffer(); writeln( "<!--?xml version=\"1.0\" encoding=\"ISO-8859-1\"?-->" ); writeln( "<program>" ); writeln( " <module>mAutodesk.mod</module>" ); mainProgram = getRedirectionBuffer(); closeRedirection(); if (FileSystem.getFilename(getOutputPath()).split( "." ).pop() == fileExtension) { error(subst(localize( "The status file extension cannot be '.%1'." ), fileExtension)); return ; } writeln( "*** Status File - Not for use ***" ); writeln( "Files are saved to: " + folder); writeln( "Main program: " + programFilename); writeln( " mAutodesk.mod" ); } function onComment(message) { if (isRedirecting()) { writeComment(message); } } function writeRobotMove(x, y, z, i, j, k, feed) { customFeed(feed); if (firstLin) { firstLin = false ; if (getProperty( "firstPointType" ) == "Joints" ) { writeMoveAbsJ(getProperty( "robotStartJ1" ), getProperty( "robotStartJ2" ), getProperty( "robotStartJ3" ), getProperty( "robotStartJ4" ), getProperty( "robotStartJ5" ), getProperty( "robotStartJ6" ), feed); writeMoveL(x, y, z, i, j, k, getProperty( "robotHeadAngle" ), feed); } else { writeMoveJ(x, y, z, i, j, k, getProperty( "robotHeadAngle" ), feed); } } else { writeMoveL(x, y, z, i, j, k, getProperty( "robotHeadAngle" ), feed); } } function writeMoveAbsJ(j1, j2, j3, j4, j5, j6, feed) { writeBlock( " MoveAbsJ [[" + jointFormat.format(j1), jointFormat.format(j2), jointFormat.format(j3), jointFormat.format(j4), jointFormat.format(j5), jointFormat.format(j6) + "],[9E9,9E9,9E9,9E9,9E9,9E9]]\\NoEOffs," + feedOutput.format(feed) + ",fine," + currentToolDataName + ";" ); } function writeMoveL(x, y, z, i, j, k, angle, feed) { // calculates quaternion from toolaxis vector and given head angle var vz = new Vector(); vz.x = i; vz.y = j; vz.z = k; var q = getQuaternionFromVector3AndRotationAngle(vz, angle); var x = xOutput.format(x); var y = yOutput.format(y); var z = zOutput.format(z); var qx = quatFormat.format(q.X); var qy = quatFormat.format(q.Y); var qz = quatFormat.format(q.Z); var qw = quatFormat.format(q.W); var feed = feedOutput.format(feed); var _weldingSeamdata = getProperty( "weldingSeamdata" ); var _weldingWelddata = getProperty( "weldingWelddata" ); var _weldingWeavedata = getProperty( "weldingWeavedata" ); var _robotZoneSmoothing = getProperty( "robotZoneSmoothing" ); if (getProperty( "weldProcess" )) { // Welding (ArcL motions needed) if (endEffectorState == 1) { if (wasEndEffectorOn == 0) { wasEndEffectorOn = 1; writeln( " ! Welding Move Starts (Arc is about to be established)" ); writeBlock( " ArcLStart [[" + x, y, z + "],[" + qw, qx, qy, qz + "],[0,0,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]]," + feed, _weldingSeamdata, _weldingWelddata + "\\Weave:=" + _weldingWeavedata + ",fine," + currentToolDataName + "\\WObj:=" + currentWorkObjectDataName + ";" ); } else { writeBlock( " ArcL [[" + x, y, z + "],[" + qw, qx, qy, qz + "],[0,0,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]]," + feed, _weldingSeamdata, _weldingWelddata + "\\Weave:=" + _weldingWeavedata + ",z" + _robotZoneSmoothing, currentToolDataName + "\\WObj:=" + currentWorkObjectDataName + ";" ); } } else { if (wasEndEffectorOn == 1) { wasEndEffectorOn = 0; writeBlock( " ArcL [[" + x, y, z + "],[" + qw, qx, qy, qz + "],[0,0,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]]," + feed, _weldingSeamdata, _weldingWelddata + "\\Weave:=" + _weldingWeavedata + ",z" + _robotZoneSmoothing, currentToolDataName + "\\WObj:=" + currentWorkObjectDataName + ";" ); writeBlock( " ! Welding Move Ends (Arc is about to be stopped)" ); writeBlock( " ArcLEnd [[" + x, y, z + "],[" + qw, qx, qy, qz + "],[0,0,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]]," + feed, _weldingSeamdata, _weldingWelddata + "\\Weave:=" + _weldingWeavedata + ",z" + _robotZoneSmoothing, currentToolDataName + "\\WObj:=" + currentWorkObjectDataName + ";" ); writeln( " WaitTime " + getProperty( "weldingWaitTime" ) + ";" ); } else { writeBlock( " MoveL [[" + x, y, z + "],[" + qw, qx, qy, qz + "],[0,0,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]]," + feed + ",z" + _robotZoneSmoothing, currentToolDataName + "\\WObj:=" + currentWorkObjectDataName + ";" ); } } } else { // Milling (MoveL only) or Additive (actually end-effector on/off switch) if (endEffectorState == 1) { if (wasEndEffectorOn == 0) { wasEndEffectorOn = 1; if (!isFFFOperation(currentSection) && currentSection.type == TYPE_ADDITIVE) { writeComment( "Additive Process Starts" ); setAdditiveProcessON(); } else { writeComment( "Cutting Move Starts" ); } } } else { if (wasEndEffectorOn == 1) { wasEndEffectorOn = 0; if (!isFFFOperation(currentSection) && currentSection.type == TYPE_ADDITIVE) { writeComment( "Additive Process Ends" ); setAdditiveProcessOFF(); } else { writeComment( "Cutting Move Ends" ); } } } writeBlock( " MoveL [[" + x, y, z + "],[" + qw, qx, qy, qz + "],[0,0,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]]," + feed + ",z" + _robotZoneSmoothing, currentToolDataName + "\\WObj:=" + currentWorkObjectDataName + ";" ); } } function writeMoveJ(x, y, z, i, j, k, angle, feed) { // calculates quaternion from toolaxis vector and given head angle var vz = new Vector(); vz.x = i; vz.y = j; vz.z = k; var q = getQuaternionFromVector3AndRotationAngle(vz, angle); writeBlock( " MoveJ [[" + xOutput.format(x), yOutput.format(y), zOutput.format(z) + "],[" + quatFormat.format(q.W), quatFormat.format(q.X), quatFormat.format(q.Y), quatFormat.format(q.Z) + "],[" + getProperty( "robotConfiguration" ) + "],[9E9,9E9,9E9,9E9,9E9,9E9]]," + feedOutput.format(feed) + ",z" + getProperty( "robotZoneSmoothing" ), currentToolDataName + "\\WObj:=" + currentWorkObjectDataName + ";" ); } function isDEDOperation() { return currentSection.strategy.indexOf( "ded_" ) != -1; } var operationCounter = 0; function onSection() { redirectToBuffer(); // main program is stored in buffer and written out in onClose cancelRotation(); if (!currentSection.isMultiAxis()) { setRotation(currentSection.workPlane); } // define the actual tool and workobject name (not available for FFF so using the properties directly) if (isFFFOperation(currentSection)) { currentToolDataName = getProperty( "robotToolData" ) + getProperty( "fffToolData" ); currentWorkObjectDataName = getProperty( "robotWorkObjectData" ) + getProperty( "fffBaseData" ); } else { currentToolDataName = getProperty( "robotToolData" ) + tool.number; currentWorkObjectDataName = getProperty( "robotWorkObjectData" ) + currentSection.workOffset; } firstLin = true ; var counter = 1; var opName; if (hasParameter( "operation-comment" )) { opName = getParameter( "operation-comment" ); } else if (hasParameter( "notes" )) { opName = getParameter( "notes" ); } else { if (isFFFOperation(currentSection)) { opName = (programName + "_" + counter); counter = counter++; } else { opName = ( "unnamed_" + counter); counter = counter++; } } opName = "m" + opName.replace(/[^a-zA-Z0-9_()+]/g, "_" ); // write toolpath name in main program // load toolpath name/tool number/spindle speed in subNames array to be written later in Autodesk.mod file if (toolpathNames.length > 0 && toolpathNames.indexOf(opName) > -1) { ++operationCounter; opName += "_" + operationCounter; } if (getProperty( "nameLimitation" )) { if (opName.length > 30) { error(subst(localize( "Toolpath Name '%1' is longer than 30 characters. Please modify it to less than 30 characters." ), opName)); } } writeBlock( " <module>" + opName + ".mod</module>" ); mainProgram += getRedirectionBuffer(); closeRedirection(); writeln( " " + opName + ".mod" ); subNames.push(currentToolDataName + "!Spindle_ON " + sOutput.format(spindleSpeed) + "@" + opName); toolpathNames.push(opName); var path = FileSystem.getCombinedPath(folder, opName + ".mod" ); var procName = ( "p" + opName.substring(1, opName.length)); redirectToFile(path); writeln( "%%%" ); writeln( " VERSION:1" ); writeln( " LANGUAGE:ENGLISH" ); writeln( "%%%" ); writeln( "" ); writeln( "MODULE " + opName); writeln( " PROC " + procName + "()" ); // set coolant code if needed setCoolant(tool.coolant); } function isFFFOperation(section) { return section.getType() == TYPE_ADDITIVE && section.getTool().type == TOOL_MARKER; } function onMovement(movement) { // We can use a simple milling (subtractive) toolpaths as additive : // ignore all the onMovement stuff for FFF since the end effector switch // is handled in the onRapid and onLinearExtrude functions if (!isFFFOperation(currentSection)) { switch (movement) { case MOVEMENT_CUTTING: case MOVEMENT_FINISH_CUTTING: writeComment( "Cutting Move Starts" ); setAdditiveProcessON(); break ; case MOVEMENT_PLUNGE: writeComment( "Plunge Move Starts" ); break ; case MOVEMENT_LEAD_IN: writeComment( "Lead In Move Starts" ); break ; case MOVEMENT_LEAD_OUT: writeComment( "Lead Out Move Starts" ); setAdditiveProcessOFF(); break ; case MOVEMENT_LINK_TRANSITION: writeComment( "Link Move Starts" ); if (getProperty( "endEffectorBehavior" ) == "OnOff" ) { setAdditiveProcessOFF(); } break ; case MOVEMENT_BRIDGING: writeComment( "Bridging Move Starts" ); break ; case MOVEMENT_LINK_DIRECT: writeComment( "Cutting Move Ends" ); break ; case MOVEMENT_RAPID: writeComment( "Rapid Move Starts" ); setAdditiveProcessOFF(); break ; case MOVEMENT_DEPOSITING: writeComment( "Depositing Move Starts" ); setAdditiveProcessON(); break ; } } } /** Machine specific output, modify as needed An end-effector is the device at the end of a robotic arm. It may consist in different gripper/tool/etc. and the activation/deactivation code depends on the end-effector type. These codes are to be customized by integrator and/or end-user. */ var endEffectorCommandOn = "==> END EFFECTOR ON: DEFINE YOUR CODE HERE IN THE POST" ; // specifies the command to turn on the end effector var endEffectorCommandOff = "==> END EFFECTOR OFF: DEFINE YOUR CODE HERE IN THE POST" ; // specifies the command to turn off the end effector function setAdditiveProcessON() { if (getProperty( "endEffectorBehavior" ) != "Off" && endEffectorState == 0) { endEffectorState = 1; if (!getProperty( "weldProcess" )) { writeComment(endEffectorCommandOn); } } } function setAdditiveProcessOFF() { if (getProperty( "endEffectorBehavior" ) != "Off" && endEffectorState == 1) { endEffectorState = 0; if (!getProperty( "weldProcess" )) { writeComment(endEffectorCommandOff); } } } /** put here the Arc welding settings: welddata, seamdata and weavedata */ function setWeldingParameters() { writeln( " PERS welddata " + getProperty( "weldingWelddata" ) + ":=[0,0,[0,0,0.0,0,0,0,0,0,0],[0,0,0,0,0,0,0,0,0]];" ); writeln( " PERS seamdata " + getProperty( "weldingSeamdata" ) + ":=[0,0,[0,0,0,0,0,0,0,0,0],0,0,0,0,0,[0,0,0,0,0,0,0,0,0],0,0,[0,0,0,0,0,0,0,0,0],0,0,[0,0,0,0,0,0,0,0,0],0];" ); writeln( " PERS weavedata " + getProperty( "weldingWeavedata" ) + ":=[0,0,0,0,0,0,0,0,0,0,0,0,0,0,0];" ); } function onDwell(seconds) { } function onSpindleSpeed(spindleSpeed) { writeBlock(sOutput.format(spindleSpeed)); } function onRadiusCompensation() { pendingRadiusCompensation = radiusCompensation; } function onRapid(_x, _y, _z) { if (isFFFOperation(currentSection)) { setAdditiveProcessOFF(); } var workPlane = currentSection.workPlane.forward; writeRobotMove(_x, _y, _z, workPlane.x, workPlane.y, workPlane.z, highFeedrate); } function onLinear(_x, _y, _z, feed) { if (pendingRadiusCompensation >= 0) { error(localize( "Radius compensation mode is not supported by robot." )); return ; } var workPlane = currentSection.workPlane.forward; writeRobotMove(_x, _y, _z, workPlane.x, workPlane.y, workPlane.z, feed); } function onLinearExtrude(_x, _y, _z, feed, _e) { if (isFFFOperation(currentSection)) { setAdditiveProcessON(); } var workPlane = currentSection.workPlane.forward; writeRobotMove(_x, _y, _z, workPlane.x, workPlane.y, workPlane.z, feed); } function onRapid5D(_x, _y, _z, _i, _j, _k) { writeRobotMove(_x, _y, _z, _i, _j, _k, highFeedrate); } function onLinear5D(_x, _y, _z, _i, _j, _k, feed) { if (pendingRadiusCompensation >= 0) { error(localize( "Radius compensation mode is not supported by robot." )); return ; } writeRobotMove(_x, _y, _z, _i, _j, _k, feed); } function onCircular(clockwise, cx, cy, cz, x, y, z, feed) { linearize(tolerance); } var forceCoolant = false ; var currentCoolantMode = COOLANT_OFF; var coolantOff = undefined; function setCoolant(coolant) { var coolantCodes = getCoolantCodes(coolant); if (Array.isArray(coolantCodes)) { if (singleLineCoolant) { writeBlock(coolantCodes.join(getWordSeparator())); } else { for ( var c in coolantCodes) { writeBlock(coolantCodes[c]); } } return undefined; } return coolantCodes; } function getCoolantCodes(coolant) { var multipleCoolantBlocks = new Array(); // create a formatted array to be passed into the outputted line if ((getProperty( "useCoolant" ) != undefined) && !getProperty( "useCoolant" )) { return undefined; } if (!coolants) { error(localize( "Coolants have not been defined." )); } if (tool.type == TOOL_PROBE) { // avoid coolant output for probing coolant = COOLANT_OFF; } if (coolant == currentCoolantMode && (!forceCoolant || coolant == COOLANT_OFF)) { return undefined; // coolant is already active } if ((coolant != COOLANT_OFF) && (currentCoolantMode != COOLANT_OFF) && (coolantOff != undefined) && !forceCoolant) { if (Array.isArray(coolantOff)) { for ( var i in coolantOff) { multipleCoolantBlocks.push(coolantOff[i]); } } else { multipleCoolantBlocks.push(coolantOff); } } forceCoolant = false ; var m; var coolantCodes = {}; for ( var c in coolants) { // find required coolant codes into the coolants array if (coolants[c].id == coolant) { coolantCodes.on = coolants[c].on; if (coolants[c].off != undefined) { coolantCodes.off = coolants[c].off; break ; } else { for ( var i in coolants) { if (coolants[i].id == COOLANT_OFF) { coolantCodes.off = coolants[i].off; break ; } } } } } if (coolant == COOLANT_OFF) { m = !coolantOff ? coolantCodes.off : coolantOff; // use the default coolant off command when an 'off' value is not specified } else { coolantOff = coolantCodes.off; m = coolantCodes.on; } if (!m) { onUnsupportedCoolant(coolant); m = 9; } else { if (Array.isArray(m)) { for ( var i in m) { multipleCoolantBlocks.push(m[i]); } } else { multipleCoolantBlocks.push(m); } currentCoolantMode = coolant; for ( var i in multipleCoolantBlocks) { if ( typeof multipleCoolantBlocks[i] == "number" ) { multipleCoolantBlocks[i] = mFormat.format(multipleCoolantBlocks[i]); } } return multipleCoolantBlocks; // return the single formatted coolant value } return undefined; } function onCommand(command) { switch (command) { case COMMAND_STOP: writeBlock( "" ); forceCoolant = true ; return ; case COMMAND_OPTIONAL_STOP: writeComment( "" ); // need variable forceCoolant = true ; return ; case COMMAND_COOLANT_ON: setCoolant(COOLANT_FLOOD); return ; case COMMAND_COOLANT_OFF: setCoolant(COOLANT_OFF); return ; case COMMAND_START_SPINDLE: onCommand(tool.clockwise ? COMMAND_SPINDLE_CLOCKWISE : COMMAND_SPINDLE_COUNTERCLOCKWISE); return ; case COMMAND_LOCK_MULTI_AXIS: return ; case COMMAND_UNLOCK_MULTI_AXIS: return ; case COMMAND_BREAK_CONTROL: return ; case COMMAND_TOOL_MEASURE: return ; default : onUnsupportedCommand(command); } } function onSectionEnd() { writeln( " ENDPROC" ); writeln( "ENDMODULE" ); closeRedirection(); } /** quaternion object */ function Quaternion (type) { this .type = type; this .W = 1; this .X = 0; this .Y = 0; this .Z = 0; } /** converts a vectorZ and a rotation angle around it to a quaternion */ function getQuaternionFromVector3AndRotationAngle(vectorZ, angleInDegrees) { // X is rotated about standard XY-plane, not provided Z-axis var vectorX = new Vector(); if (Math.abs(vectorZ.x) == 1) { // if tool axis is align with X axis vectorX = Matrix.getXRotation(toRad(angleInDegrees)).transposed.multiply( new Vector(1, 0, 0)); } else if (Math.abs(vectorZ.y) == 1) { // if tool axis is align with Y axis vectorX = Matrix.getYRotation(toRad(angleInDegrees)).transposed.multiply( new Vector(1, 0, 0)); } else { // any other cases vectorX = Matrix.getZRotation(toRad(angleInDegrees)).transposed.multiply( new Vector(1, 0, 0)); } // X and Z form a non-orthogonal matrix, so cannot use standard matrix calculations var yAxis = Vector.cross(vectorZ, vectorX).normalized; var xAxis = Vector.cross(yAxis, vectorZ).normalized; var yAxis = Vector.cross(vectorZ, xAxis).normalized; m = new Matrix(xAxis, yAxis, vectorZ).transposed; if (getProperty( "flipToolFrame" )) { m = Matrix.getAxisRotation( new Vector(0, 1, 0), Math.PI).multiply(m); } var q = getQuaternionFromMatrix3x3(m); return q; } /** converts a rotation matrix 3x3 to a quaternion */ function getQuaternionFromMatrix3x3(rotationMatrix) { var m00 = rotationMatrix.getElement(0, 0); var m01 = rotationMatrix.getElement(1, 0); var m02 = rotationMatrix.getElement(2, 0); var m10 = rotationMatrix.getElement(0, 1); var m11 = rotationMatrix.getElement(1, 1); var m12 = rotationMatrix.getElement(2, 1); var m20 = rotationMatrix.getElement(0, 2); var m21 = rotationMatrix.getElement(1, 2); var m22 = rotationMatrix.getElement(2, 2); var qw = 0; var qx = 0; var qy = 0; var qz = 0; var s = 0; // compute the quaternion if (m00 + m11 + m22 > 2.99999999) { qw = 1; qx = 0; qy = 0; qz = 0; } else if (m00 + m11 + m22 + 1 > 0.00000001) { S = Math.sqrt(m00 + m11 + m22 + 1) * 2; qw = 0.25 * S; qx = (m21 - m12) / S; qy = (m02 - m20) / S; qz = (m10 - m01) / S; } else if (m00 > m11 && m00 > m22) { if (1.0 + m00 - m11 - m22 <= 0) {error(localize( "Quaternion calculation error" ));} S = Math.sqrt(1.0 + m00 - m11 - m22) * 2; qw = (m21 - m12) / S; qx = 0.25 * S; qy = (m01 + m10) / S; qz = (m02 + m20) / S; } else if (m11 > m22) { if (1.0 + m11 - m00 - m22 <= 0) {error(localize( "Quaternion calculation error" ));} S = Math.sqrt(1.0 + m11 - m00 - m22) * 2; qw = (m02 - m20) / S; qx = (m01 + m10) / S; qy = 0.25 * S; qz = (m12 + m21) / S; } else { if (1.0 + m22 - m00 - m11 <= 0) {error(localize( "Quaternion calculation error" ));} S = Math.sqrt(1.0 + m22 - m00 - m11) * 2; qw = (m10 - m01) / S; qx = (m02 + m20) / S; qy = (m12 + m21) / S; qz = 0.25 * S; } // return result var q = new Quaternion(); q.W = qw; q.X = qx; q.Y = qy; q.Z = qz; return q; } function autodeskOut() { speeddata.sort(); redirectToFile(FileSystem.getCombinedPath(folder, "mAutodesk.mod" )); writeln( "%%%" ); writeln( " VERSION:1" ); writeln( " LANGUAGE:ENGLISH" ); writeln( "%%%" ); writeln( "" ); writeln( "MODULE mAUTODESK" ); writeln( "" ); for ( var i = 0; i < speeddata.length; ++i) { var number = speeddata[i].slice(1, speeddata[i].length); writeln( " PERS speeddata " + speeddata[i] + ":=[" + number + ",500,5000,1000];" ); } writeln( "" ); if (getProperty( "weldProcess" )) { setWeldingParameters(); writeln( "" ); } writeln( " PROC main()" ); if (hasGlobalParameter( "generated-by" )) { var value = getGlobalParameter( "generated-by" ); writeBlock( " ! Generated by AUTODESK " + value); } if (getProperty( "writeDateAndTime" )) { var d = new Date(); writeBlock(localize( " ! Creation date" ) + ": " + d.toLocaleDateString() + " " + d.toLocaleTimeString()); } writeln( "" ); writeln( " ! Acceleration and jerk/ramp (percentage)" ); writeln( " AccSet 20,20;" ); writeln( "" ); writeln( " ! Configurations" ); writeln( " ConfJ\\On;" ); writeln( " ConfL\\Off;" ); var prevTool = 9999; var prevSpindle = 9999; // write total list of toolpaths and tool change/spindle speed only when changed for ( var i = 0; i < subNames.length; ++i) { var toolNo = subNames[i].slice(0, subNames[i].indexOf( "!" )); subNames[i] = subNames[i].slice(subNames[i].indexOf( "!" ), subNames[i].length); var spindleSpe = subNames[i].slice(0, subNames[i].indexOf( "@" )); subNames[i] = subNames[i].slice(subNames[i].indexOf( "@" ) + 1, subNames[i].length); if (toolNo != prevTool) { writeln( "" ); writeln( " ! Load Tool" ); writeln( " !Tool_Change " + toolNo + ";" ); writeln( "" ); prevTool = toolNo; } if (spindleSpe != prevSpindle) { writeln( " ! Spindle On/Speed" ); writeln( " " + spindleSpe + ";" ); writeln( "" ); prevSpindle = spindleSpe; } var procName = ( "p" + subNames[i].substring(1, subNames[i].length)); writeln( " " + procName + ";" ); } writeln( "" ); writeln( " ! Spindle Off" ); writeln( " !Spindle_OFF;" ); writeln( "" ); writeln( " ConfJ\\On;" ); writeln( " ConfL\\On;" ); writeln( " Stop;" ); writeln( " ENDPROC" ); writeln( "ENDMODULE" ); closeRedirection(); return ; } function customFeed(feed) { var nonStandard = predefinedspeed.indexOf(feedOutput.format(feed)); if (speeddata.length == 0) { if (nonStandard == -1) { speeddata.push(feedOutput.format(feed)); } } else { var i = 0; do { if (speeddata[i] == feedOutput.format(feed)) { break ; } i++; } while (i < speeddata.length); if (i == speeddata.length && nonStandard == -1) { speeddata.push(feedOutput.format(feed)); } } } function onClose() { // write out main program redirectToFile(FileSystem.getCombinedPath(folder, programFilename)); write(mainProgram); writeBlock( "</program>" ); closeRedirection(); // create mAutodesk.mod file autodeskOut(); } function setProperty(property, value) { properties[property].current = value; } |