/**
  Copyright (C) 2012-2021 by Autodesk, Inc.
  All rights reserved.

  Yaskawa-Motoman post processor configuration.

  $Revision: 43470 147f5cf60e9217cf9c3365dc511a0f631d89bb16 $
  $Date: 2021-10-13 20:53:32 $

  FORKID {1E81BFC1-707D-44BF-9F1A-0FF86A9A365F}
*/

///////////////////////////////////////////////////////////////////////////////
//     CUSTOM NC COMMANDS - search for 'Machine specific output, modify as needed'
//
//     endEffectorCommandOn   =ARCON - Modify this variable to define the commands to turn ON the end effector, if needed
//     endEffectorCommandOff  =ARCOF - Modify this variable to define the commands to turn OFF the end effector, if needed
//
///////////////////////////////////////////////////////////////////////////////

description = "Yaskawa-Motoman";
vendor = "Yaskawa-Motoman";
vendorUrl = "https://www.motoman.com/en-us";
legal = "Copyright (C) 2012-2021 by Autodesk, Inc.";
certificationLevel = 2;
minimumRevision = 45702;

longDescription = "Generic Yaskawa-Motoman post. Please refer to the User Guide for programming specification and sample. Always validate with virtual controller before loading any toolpath on your Robot.";

extension = "JBI";
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 = {
  endEffectorBehavior: {
    title      : "End-effector state",
    description: "Set the end-effector state (including behavior during flat toolpath transitions).",
    group      : "process",
    type       : "enum",
    values     : [
      {title:"OFF", id:"Off"},
      {title:"ON + links ON", id:"On"},
      {title:"ON + links OFF", id:"OnOff"}
    ],
    value: "Off",
    scope: "post"
  },
  robotHeadAngle: {
    title      : "Robot head angle",
    description: "Robot head angle around tool axis",
    group      : "process",
    type       : "number",
    value      : 30,
    scope      : "post"
  },
  flipToolFrame: {
    title      : "Flip tool frame",
    description: "Flip the tool frame (Z- is along the tool axis).",
    group      : "configuration",
    type       : "boolean",
    value      : true,
    scope      : "post"
  },
  robotAcceleration: {
    title      : "Robot acceleration (%)",
    description: "Robot acceleration (%)",
    group      : "parameters",
    type       : "integer",
    value      : 25,
    scope      : "post"
  },
  robotAccuracy: {
    title      : "Robot accuracy (Position Level)",
    description: "Robot accuracy (Position Level)",
    group      : "parameters",
    type       : "integer",
    value      : 1,
    scope      : "post"
  },
  robotConfiguration: {
    title      : "Robot configuration (RCONF)",
    description: "Robot arm configuration (RCONF)",
    group      : "parameters",
    type       : "string",
    value      : "1,0,0,0,0,0",
    scope      : "post"
  },
  robotFrameData: {
    title      : "Robot Frame",
    description: "WCS number (FRAME) used for FFF toolpath",
    group      : "fff",
    type       : "integer",
    value      : 1,
    scope      : "post"
  },
  robotToolData: {
    title      : "Robot Tool",
    description: "Tool number (TOOL) used for FFF toolpath",
    group      : "fff",
    type       : "integer",
    value      : 1,
    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"
  },
  useCoolant: {
    title      : "Use coolant",
    description: "Specifies if Robot needs Coolant Codes",
    group      : "general",
    type       : "boolean",
    value      : false,
    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"
  },
  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"
  }
};
groupDefinitions = {
  process      : {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},
  fff          : {title:"FFF Settings", description:"FFF Settings", collapsed:true, order:3},
  general      : {title:"General", description:"Other post options", collapsed:true, order:4}
};

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:true, trim:false});
var abcFormat = createFormat({decimals:3, forceDecimal:true, trim:false});
var feedFormat = createFormat({decimals:(unit == MM ? 0 : 0), forceDecimal:false, scale:1.0 / 60.0}); // mm/min -> mm/s
var toolFormat = createFormat({decimals:0});
var rpmFormat = createFormat({decimals:0});
var dateFormat = createFormat({decimals:0, width:2, zeropad:true});
var lineFormat = createFormat({decimals:0, width:5, zeropad:true});

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 r1Output = createVariable({prefix:"", force:true}, abcFormat);
var r2Output = createVariable({prefix:"", force:true}, abcFormat);
var r3Output = createVariable({prefix:"", force:true}, abcFormat);
var lineOutput = createVariable({prefix:"C", force:true}, lineFormat);
var dateOutput = createVariable({prefix:"", force:true}, dateFormat);
var feedOutput = createVariable({prefix:"", force:true}, feedFormat);
var sOutput = createVariable({prefix:"", force:true}, rpmFormat);

var forceSpindleSpeed = false;
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 endEffectorState = 0; // initial state of the end effector (0 =off)
// Machine specific output, modify as needed
var endEffectorCommandOn = "ARCON"; // specifies the command to turn on the end effector
var endEffectorCommandOff = "ARCOF"; // specifies the command to turn off the end effector

var subfolderPath;
var lineCounter = 0; // counter used for toolpath lines
var lines = new Array(); // array used to write toolpath lines in the footer
var coords = new Array(); // array used to write toolpath lines in the footer
var toolpathNames = new Array();

/**
  Writes the specified block.
*/
function writeBlock() {
  writeWords(arguments);
}
/**
  Filter permitted characters from operation name.
*/
function filterPermittedChar(text) {
  return text.replace(/[^a-zA-Z0-9_()+]/g, "_");
}

/**
  Formats a comment.
*/
function formatComment(text) {
  return "' " + String(text).replace(/[()]/g, "");
}

/**
  Output a comment.
*/
function writeComment(text) {
  if (isRedirecting()) {
    coords.push(formatComment(text));
  } else {
    writeln(formatComment(text));
  }
}

function onOpen() {
  // Machine requires output only in MM
  unit = MM;

  // create subfolder if requested
  if (getProperty("useSubfolder")) {
    subfolderPath = FileSystem.getCombinedPath(FileSystem.getFolderPath(getOutputPath()), programName);
    if (!FileSystem.isFolder(subfolderPath)) {
      FileSystem.makeFolder(subfolderPath);
    }
  }

  writeBlock("/JOB");
  writeBlock("//NAME " + FileSystem.replaceExtension(FileSystem.getFilename(getOutputPath().toUpperCase()), ""));
  writeBlock("//POS");
  writeBlock("///NPOS 0,0,0,0,0,0");
  writeBlock("//INST");
  if (getProperty("writeDateAndTime")) {
    writeDate();
  }

  writeBlock("///ATTR SC,RW");
  writeBlock("NOP");

  if (hasGlobalParameter("generated-by")) {
    var value = getGlobalParameter("generated-by");
    writeComment("By Autodesk " + value);
  }

  // set coolant code if needed
  setCoolant(tool.coolant);
}

function onComment(message) {
  writeComment(message);
}

/**
  Writes the right robot move (first point joint, others as linear)
*/
function writeRobotMove(x, y, z, i, j, k, feed) {
  if (firstLin) {
    writeJoint(x, y, z, i, j, k, getProperty("robotHeadAngle"), feed);
    firstLin = false;
  } else {
    writeLinear(x, y, z, i, j, k, getProperty("robotHeadAngle"), feed);
  }
}

/**
  Joint move
*/
function writeJoint(x, y, z, i, j, k, angle, feed) {
  var vz = new Vector();
  vz.x = i;
  vz.y = j;
  vz.z = k;
  var ea = getMotomanEulerAngleFromVectorAndRotationAngle(vz, angle);
  lines.push(lineOutput.format(lineCounter) + "=" + xOutput.format(x) + "," + yOutput.format(y) + "," + zOutput.format(z) + "," + r1Output.format(ea.x) + "," + r2Output.format(ea.y) + "," + r3Output.format(ea.z));
  coords.push("MOVJ " + lineOutput.format(lineCounter++) + " VJ=" + feedOutput.format(feed));
}

/**
  Linear move
*/
function writeLinear(x, y, z, i, j, k, angle, feed) {
  var vz = new Vector();
  vz.x = i;
  vz.y = j;
  vz.z = k;
  var ea = getMotomanEulerAngleFromVectorAndRotationAngle(vz, angle);
  lines.push(lineOutput.format(lineCounter) + "=" + xOutput.format(x) + "," + yOutput.format(y) + "," + zOutput.format(z) + "," + r1Output.format(ea.x) + "," + r2Output.format(ea.y) + "," + r3Output.format(ea.z));
  coords.push("MOVL " + lineOutput.format(lineCounter++) + " V=" + feedOutput.format(feed) + " PL=LB000 ACC=LB001 DEC=LB001");
}

var operationCounter = 0;
function onSection() {
  lineCounter = 0; // reset toolpath line counter
  firstLin = true;
  cancelRotation();
  if (!currentSection.isMultiAxis()) {
    setRotation(currentSection.workPlane);
  }

  var counter = 1;
  var opName;

  if (isFFFOperation(currentSection)) {
    opName = (programName + "_" + counter);
    counter = counter++;
  } else {
    if (hasParameter("operation-comment")) {
      opName = getParameter("operation-comment");
    } else if (hasParameter("notes")) {
      opName = getParameter("notes");
    } else {
      opName = ("unnamed_" + counter);
      counter = counter++;
    }
  }

  opName = "s" + filterPermittedChar(opName);

  if (getProperty("useSubfolder")) {
    folder = subfolderPath;
  } else {
    folder = FileSystem.getFolderPath(getOutputPath());
  }

  // write toolpath name in Array to check for duplicated names
  if (toolpathNames.length > 0 && toolpathNames.indexOf(opName) > -1) {
    ++operationCounter;
    opName += "_" + operationCounter;
  }
  toolpathNames.push(opName);

  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));
    }
  }

  var path = FileSystem.getCombinedPath(folder, opName + ".JBI");

  // write toolpath name in main program
  writeBlock("CALL JOB:" + opName);

  // start writing in subprogram
  redirectToFile(path);
  writeBlock("/JOB");
  writeBlock("//NAME " + opName);
  writeBlock("//POS");
}

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:
      coords.push("' Cutting Move Starts");
      setAdditiveProcessOn();
      break;
    case MOVEMENT_PLUNGE:
      coords.push("' Plunge Move Starts");
      break;
    case MOVEMENT_LEAD_IN:
      coords.push("' Lead In Move Starts");
      break;
    case MOVEMENT_LEAD_OUT:
      if (getProperty("endEffectorBehavior") == "OnOff") {
        setAdditiveProcessOff();
      }
      coords.push("' Lead Out Move Starts");
      break;
    case MOVEMENT_LINK_TRANSITION:
      if (getProperty("endEffectorBehavior") == "OnOff") {
        setAdditiveProcessOff();
      }
      coords.push("' Link Move Starts");
      break;
    case MOVEMENT_BRIDGING:
      coords.push("' Bridging Move Starts");
      break;
    case MOVEMENT_LINK_DIRECT:
      coords.push("' Cutting Move Ends");
      break;
    case MOVEMENT_RAPID:
      setAdditiveProcessOff();
      coords.push("' Rapid Move Starts");
      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.

function setAdditiveProcessOn() {
  if (getProperty("endEffectorBehavior") != "Off" && endEffectorState == 0) {
    coords.push(endEffectorCommandOn);
    endEffectorState = 1;
  }
}

function setAdditiveProcessOff() {
  if (getProperty("endEffectorBehavior") != "Off" && endEffectorState == 1) {
    coords.push(endEffectorCommandOff);
    endEffectorState = 0;
  }
}

function onDwell(seconds) {
}

function onSpindleSpeed(spindleSpeed) {
  writeComment("Spindle = " + sOutput.format(spindleSpeed) + " RPM");
}

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) {
  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 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) {
    return undefined; // coolant is already active
  }
  if ((coolant != COOLANT_OFF) && (currentCoolantMode != COOLANT_OFF) && (coolantOff != undefined)) {
    if (Array.isArray(coolantOff)) {
      for (var i in coolantOff) {
        multipleCoolantBlocks.push(coolantOff[i]);
      }
    } else {
      multipleCoolantBlocks.push(coolantOff);
    }
  }

  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:
    forceSpindleSpeed = true;
    return;
  case COMMAND_OPTIONAL_STOP:
    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() {
  var toolNumber = isFFFOperation(currentSection) ? getProperty("robotToolData") : tool.number;
  var workOffsetLocal = isFFFOperation(currentSection) ? getProperty("robotFrameData") : currentSection.workOffset;
  if (workOffsetLocal == 0) {
    error(localize("Robot user frame has not been specified. Define it as WCS value, editing current Setup."));
  }

  writeBlock("///NPOS " + lineCounter + ",0,0,0,0,0");
  writeBlock("///USER " + workOffsetLocal);
  writeBlock("///TOOL " + toolFormat.format(toolNumber));
  writeBlock("///POSTYPE USER");
  writeBlock("///RECTAN");
  writeBlock("///RCONF " + getProperty("robotConfiguration"));

  for (var i = 0; i < lines.length; ++i) {
    var lineOut = lines[i];
    writeBlock(lineOut);
  }

  writeBlock("//INST");
  if (getProperty("writeDateAndTime")) {
    writeDate();
  }

  writeBlock("///ATTR SC,RW,RJ");
  writeBlock("////FRAME USER " + workOffsetLocal);
  writeBlock("///GROUP1 RB1");
  writeBlock("///LVARS 2,0,0,0,0,0,0,0");
  writeBlock("NOP");
  if (hasGlobalParameter("generated-by")) {
    var value = getGlobalParameter("generated-by");
    writeComment("By Autodesk " + value);
  }
  writeComment("Tool = " + toolFormat.format(toolNumber));
  onSpindleSpeed(spindleSpeed);
  writeComment("Set Position Level");
  writeBlock("SET LB000 " + getProperty("robotAccuracy"));
  writeComment("Set Acceleration");
  writeBlock("SET LB001 " + getProperty("robotAcceleration"));
  writeComment("Program Start");

  for (var i = 0; i < coords.length; ++i) {
    var coordOut = coords[i];
    writeBlock(coordOut);
    if (i == 0) {
      writeComment("First Toolpath Point");
    }
  }
  writeComment("Last Toolpath Point");
  writeBlock("END");
  closeRedirection();
}

/**
  converts a vectorZ and a rotation angle around it to Motoman Euler angles
*/
function getMotomanEulerAngleFromVectorAndRotationAngle(vectorZ, angleInDegrees) {
  // X is rotated about standard XY-plane, not provided Z-axis
  var 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);
  var xAxis = Vector.cross(yAxis, vectorZ);
  var yAxis = Vector.cross(vectorZ, xAxis);

  m = new Matrix(xAxis, yAxis, vectorZ).transposed;

  if (getProperty("flipToolFrame")) {
    m = Matrix.getAxisRotation(new Vector(0, 1, 0), Math.PI).multiply(m);
  }

  ea = new Vector();
  var ea = m.transposed.getEuler2(EULER_ZYZ_R).toDeg();

  return ea;
}

function writeDate() {
  var date = new Date();
  writeBlock("///DATE " + date.getFullYear().toString() + "/" + dateOutput.format(date.getMonth() + 1) + "/" + dateOutput.format(date.getDate()) + " " + dateOutput.format(date.getHours()) + ":" + dateOutput.format(date.getMinutes()));
}

function onTerminate() {
  if (getProperty("useSubfolder")) {
    var outputPath = getOutputPath();
    var programFilename = FileSystem.getFilename(outputPath);
    var newFolder = subfolderPath + "\\" + programFilename;
    FileSystem.copyFile(outputPath, newFolder);
    FileSystem.remove(outputPath);

    var file = new TextFile(FileSystem.getFolderPath(getOutputPath()) + "\\" + programFilename, true, "ansi");
    file.writeln("This is a dummy file.");
    file.writeln("Your program files are located here: " + subfolderPath);
    file.close();
  }
}

function onClose() {
  writeBlock("END");
}

function setProperty(property, value) {
  properties[property].current = value;
}