diff --git a/.gitignore b/.gitignore index 6a56b95d..d4028018 100644 --- a/.gitignore +++ b/.gitignore @@ -7,6 +7,10 @@ ENV/ env.bak/ venv.bak/ +#pyyinstaller +build +dist + #logs log.txt alog.txt @@ -18,3 +22,8 @@ alog.txt __pycache__/ *.py[cod] *$py.class +Services/tp.py +Services/tr.py +Services/pijson.txt +Services/pijsonRT.txt +File/wiicontrol.code-workspace diff --git a/Actions/HoleySimulationKinematics.py b/Actions/HoleySimulationKinematics.py new file mode 100644 index 00000000..b2b7ea11 --- /dev/null +++ b/Actions/HoleySimulationKinematics.py @@ -0,0 +1,606 @@ +import math +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs + + +class Kinematics(MakesmithInitFuncs): + ''' + The Kinematics module relates the lengths of the chains to the position of the cutting head + in X-Y space. + ''' + + l = 310.0 # horizontal distance between sled attach points + s = 139.0 # vertical distance between sled attach points and bit + h = math.sqrt((l / 2) * (l / 2) + s * s) # distance between sled attach point and bit + h3 = 79.0 # distance from bit to sled center of mass + D = 2978.4 # distance between sprocket centers + R = 10.2 # sprocket radius + machineHeight = 1219.2 # this is 4 feet in mm + machineWidth = 2438.4 # this is 8 feet in mm + motorOffsetY = 463.0 # vertical distance from the corner of the work area to the sprocket center + chain1Offset = 0 # number of links +,- that have slipped + chain2Offset = 0 # number of links +,- that have slipped + + x = 2708.4 + y = 270 + + # utility variables + DegPerRad = 360 / (4 * math.atan(1)) + Time = 0 + Mirror = 0 + + # Definition of angles + # Gamma, angle of left chain + # Lamda, angle of right chain + # Phi, tilt of sled + # Theta, angle between chains and bit (corners of triangle formed by l, s, h) + + # Calculation tolerances + MaxError = 0.01 + MaxTries = 10 + DeltaPhi = 0.01 + DeltaY = 0.01 + + # Criterion Computation Variables + Phi = -0.2 + TanGamma = 0 + TanLambda = 0 + Y1Plus = 0 + Y2Plus = 0 + if (l < 1.0): + Theta = 0 + else: + Theta = math.atan(2 * s / l) + Psi1 = Theta - Phi + Psi2 = Theta + Phi + Tries = 0 + Jac = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0] + Solution = [0, 0, 0] + Crit = [0, 0, 0] + # Offsetx1 = 0 + # Offsetx2 = 0 + # Offsety1 = 0 + # Offsety2 = 0 + # SinPsi1 = 0 + # CosPsi1 = 0 + # SinPsi2 = 0 + # CosPsi2 = 0 + # SinPsi1D = 0 + # CosPsi1D = 0 + # SinPsi2D = 0 + # CosPsi2D = 0 + # MySinPhi = 0 + # MySinPhiDelta = 0 + + # intermediate output + Lambda = 0 + Gamma = 0 + + # Motor axes length to the bit for triangular kinematics + Motor1Distance = 0 # left motor axis distance to sled + Motor2Distance = 0 # right motor axis distance to sled + + # output = chain lengths measured from 12 o'clock + Chain1 = 0 # left chain length + Chain2 = 0 # right chain length + + leftChainTolerance = 0 + rightChainTolerance = 0 + chainDensity = .0013 # N/mm + chainElasticity = 5.1685e-6 # mm/mm/N + sledWeight = 97.9 # N + + i = 0 + + rotationDiskRadius = 100 + chainSagCorrection = 0 + chainOverSprocket = 1 + _xCordOfMotor = D / 2 + _yCordOfMotor = machineHeight / 2 + motorOffsetY + isQuadKinematics = True + + def _verifyValidTarget(self, xTarget, yTarget): + # If the target point is beyond one of the edges of the board, the machine stops at the edge + + if (xTarget < -self.machineWidth / 2): + xTarget = -self.machineWidth / 2 + + elif (xTarget > self.machineWidth / 2): + xTarget = self.machineWidth / 2 + + elif (yTarget > self.machineHeight / 2): + yTarget = self.machineHeight / 2 + + elif (yTarget < -self.machineHeight / 2): + yTarget = -self.machineHeight / 2 + + def recomputeGeometry(self): + ''' + Some variables are computed on class creation for the geometry of the machine to reduce overhead, + calling this function regenerates those values. + ''' + self.h = math.sqrt((self.l / 2) * (self.l / 2) + self.s * self.s) + self.Theta = math.atan(2 * self.s / self.l) + self.Psi1 = self.Theta - self.Phi + self.Psi2 = self.Theta + self.Phi + + self._xCordOfMotor = self.D / 2 + self._yCordOfMotor = self.machineHeight / 2 + self.motorOffsetY + + def inverse(self, xTarget, yTarget): + ''' + + Compute the lengths of chain needed to reach a target XY position + + ''' + if self.isQuadKinematics: + return self.quadrilateralInverse(xTarget, yTarget) + else: + return self.triangularInverse(xTarget, yTarget) + + def triangularInverse(self, xTarget, yTarget): + ''' + + The inverse kinematics (relating an xy coordinate pair to the required chain lengths to hit that point) + function for a triangular set up where the chains meet at a point, or are arranged so that they simulate + meeting at a point. + + ''' + + # Confirm that the coordinates are on the wood + self._verifyValidTarget(xTarget, yTarget) + + Motor1Distance = math.sqrt( + math.pow((-1 * self._xCordOfMotor - xTarget), 2) + math.pow((self._yCordOfMotor - yTarget), 2)) + Motor2Distance = math.sqrt( + math.pow((self._xCordOfMotor - xTarget), 2) + math.pow((self._yCordOfMotor - yTarget), 2)) + + # Calculate the chain angles from horizontal, based on if the chain connects to the sled from the top or bottom of the sprocket + if self.chainOverSprocket == 1: + Chain1Angle = math.asin((self._yCordOfMotor - yTarget) / Motor1Distance) + math.asin( + self.R / Motor1Distance) + Chain2Angle = math.asin((self._yCordOfMotor - yTarget) / Motor2Distance) + math.asin( + self.R / Motor2Distance) + + Chain1AroundSprocket = self.R * Chain1Angle + Chain2AroundSprocket = self.R * Chain2Angle + + xTangent1 = -self._xCordOfMotor + self.R * math.sin(Chain1Angle) + yTangent1 = self._yCordOfMotor + self.R * math.cos(Chain1Angle) + + xTangent2 = self._xCordOfMotor - self.R * math.sin(Chain2Angle) + yTangent2 = self._yCordOfMotor + self.R * math.cos(Chain2Angle) + else: + Chain1Angle = math.asin((self._yCordOfMotor - yTarget) / Motor1Distance) - math.asin( + self.R / Motor1Distance) + Chain2Angle = math.asin((self._yCordOfMotor - yTarget) / Motor2Distance) - math.asin( + self.R / Motor2Distance) + + Chain1AroundSprocket = self.R * (3.14159 - Chain1Angle) + Chain2AroundSprocket = self.R * (3.14159 - Chain2Angle) + + xTangent1 = -self._xCordOfMotor - self.R * math.sin(Chain1Angle) + yTangent1 = self._yCordOfMotor - self.R * math.cos(Chain1Angle) + + xTangent2 = self._xCordOfMotor + self.R * math.sin(Chain2Angle) + yTangent2 = self._yCordOfMotor - self.R * math.cos(Chain2Angle) + + # Calculate the straight chain length from the sprocket to the bit + Chain1Straight = math.sqrt(math.pow(Motor1Distance, 2) - math.pow(self.R, 2)) + Chain2Straight = math.sqrt(math.pow(Motor2Distance, 2) - math.pow(self.R, 2)) + + # TensionDenominator=(x_l y_r- x_r y_l- x_l y_t +x_t y_l +x_r y_t -x_t y_r) + TensionDenominator = ( + xTangent1 * yTangent2 - xTangent2 * yTangent1 - xTangent1 * yTarget + xTarget * yTangent1 + xTangent2 * yTarget - xTarget * yTangent2) + + # Total vertical force is sled weight, plus half the two chain weights + TotalWeight = self.sledWeight + 0.5 * self.chainDensity * (Chain1Straight + Chain2Straight) + + # T_l = -( w *sqrt( pow(x_l -x_t ,2.0)+pow( y_l -y_t ,2.0)) (x_r -x_t)) /TensionDenominator + Tension1 = - (TotalWeight * math.sqrt(math.pow(xTangent1 - xTarget, 2) + math.pow(yTangent1 - yTarget, 2)) * ( + xTangent2 - xTarget)) / TensionDenominator + + # T_r = ( w *sqrt( pow(x_r -x_t ,2.0)+pow( y_r -y_t ,2.0)) (x_l -x_t))/(x_ly_r-x_ry_l-x_ly_t+x_ty_l+x_ry_t-x_ty_r) + Tension2 = (TotalWeight * math.sqrt(math.pow(xTangent2 - xTarget, 2) + math.pow(yTangent2 - yTarget, 2)) * ( + xTangent1 - xTarget)) / TensionDenominator + + HorizontalTension = Tension1 * (xTarget - xTangent1) / Chain1Straight + + # Calculation of horizontal component of tension for two chains should be equal, as validation step + # HorizontalTension1=Tension1*(xTarget-xTangent1)/Chain1Straight + # HorizontalTension2=Tension2*(xTangent2-xTarget)/Chain2Straight + + # Calculation of vertical force due to tension, to validate tension calculation + # VerticalForce=Tension1*(yTangent1-yTarget)/Chain1Straight+Tension2*(yTangent2-yTarget)/Chain2Straight + + a1 = HorizontalTension / self.chainDensity + a2 = HorizontalTension / self.chainDensity + # print("Horizontal Tension ",HorizontalTension) + + # Catenary Equation + Chain1 = math.sqrt( + math.pow(2 * a1 * math.sinh((xTarget - xTangent1) / (2 * a1)), 2) + math.pow(yTangent1 - yTarget, 2)) + Chain2 = math.sqrt( + math.pow(2 * a2 * math.sinh((xTangent2 - xTarget) / (2 * a2)), 2) + math.pow(yTangent2 - yTarget, 2)) + CatenaryDelta1 = Chain1 - Chain1Straight + CatenaryDelta2 = Chain2 - Chain2Straight + # print("Catenary Delta 1 ",CatenaryDelta1) + # print("Catenary Delta 2 ",CatenaryDelta2) + + # Calculate total chain lengths accounting for sprocket geometry and chain sag + Chain1ElasticityDelta = Chain1 - Chain1 / (1 + Tension1 * self.chainElasticity) + Chain2ElasticityDelta = Chain2 - Chain2 / (1 + Tension2 * self.chainElasticity) + # print("Chain1 Elasticity Delta ",Chain1ElasticityDelta) + # print("Chain2 Elasticity Delta ",Chain2ElasticityDelta) + + Chain1 = Chain1AroundSprocket + Chain1 / (1.0 + self.leftChainTolerance / 100.0) / ( + 1 + Tension1 * self.chainElasticity) + Chain2 = Chain2AroundSprocket + Chain2 / (1.0 + self.rightChainTolerance / 100.0) / ( + 1 + Tension2 * self.chainElasticity) + + # Subtract of the virtual length which is added to the chain by the rotation mechanism + Chain1 = Chain1 - self.rotationDiskRadius + Chain2 = Chain2 - self.rotationDiskRadius + + return Chain1, Chain2 + + def quadrilateralInverse(self, xTarget, yTarget): + + ''' + + Take the XY position and return chain lengths. + + ''' + + # Confirm that the coordinates are on the wood + self._verifyValidTarget(xTarget, yTarget) + + # coordinate shift to put (0,0) in the center of the plywood from the left sprocket + self.x = (self.D / 2.0) + xTarget + self.y = (self.machineHeight / 2.0) + self.motorOffsetY - yTarget + + # Coordinates definition: + # x -->, y | + # v + # (0,0) at center of left sprocket + # upper left corner of plywood (270, 270) + + Tries = 0 # initialize + if ( + self.x > self.D / 2.0): # the right half of the board mirrors the left half so all computations are done using left half coordinates. + self.x = self.D - self.x # Chain lengths are swapped at exit if the x,y is on the right half + self.Mirror = True + + else: + self.Mirror = False + + self.TanGamma = self.y / self.x + self.TanLambda = self.y / (self.D - self.x) + self.Y1Plus = self.R * math.sqrt(1 + self.TanGamma * self.TanGamma) + self.Y2Plus = self.R * math.sqrt(1 + self.TanLambda * self.TanLambda) + + self._MyTrig() + # self.Psi1 = self.Theta - self.Phi + # self.Psi2 = self.Theta + self.Phi + # These criteria will be zero when the correct values are reached + # They are negated here as a numerical efficiency expedient + + self.Crit[0] = - self._moment(self.Y1Plus, self.Y2Plus, self.Phi, self.MySinPhi, self.SinPsi1, self.CosPsi1, + self.SinPsi2, self.CosPsi2) + self.Crit[1] = - self._YOffsetEqn(self.Y1Plus, self.x - self.h * self.CosPsi1, self.SinPsi1) + self.Crit[2] = - self._YOffsetEqn(self.Y2Plus, self.D - (self.x + self.h * self.CosPsi2), self.SinPsi2) + + while (Tries <= self.MaxTries): + if (abs(self.Crit[0]) < self.MaxError): + if (abs(self.Crit[1]) < self.MaxError): + if (abs(self.Crit[2]) < self.MaxError): + break + + # estimate the tilt angle that results in zero net _moment about the pen + # and refine the estimate until the error is acceptable or time runs out + + # Estimate the Jacobian components + + self.Jac[0] = (self._moment(self.Y1Plus, self.Y2Plus, self.Phi + self.DeltaPhi, self.MySinPhiDelta, + self.SinPsi1D, self.CosPsi1D, self.SinPsi2D, self.CosPsi2D) + self.Crit[ + 0]) / self.DeltaPhi + self.Jac[1] = (self._moment(self.Y1Plus + self.DeltaY, self.Y2Plus, self.Phi, self.MySinPhi, self.SinPsi1, + self.CosPsi1, self.SinPsi2, self.CosPsi2) + self.Crit[0]) / self.DeltaY + self.Jac[2] = (self._moment(self.Y1Plus, self.Y2Plus + self.DeltaY, self.Phi, self.MySinPhi, self.SinPsi1, + self.CosPsi1, self.SinPsi2, self.CosPsi2) + self.Crit[0]) / self.DeltaY + self.Jac[3] = (self._YOffsetEqn(self.Y1Plus, self.x - self.h * self.CosPsi1D, self.SinPsi1D) + self.Crit[ + 1]) / self.DeltaPhi + self.Jac[4] = (self._YOffsetEqn(self.Y1Plus + self.DeltaY, self.x - self.h * self.CosPsi1, self.SinPsi1) + + self.Crit[1]) / self.DeltaY + self.Jac[5] = 0.0 + self.Jac[6] = (self._YOffsetEqn(self.Y2Plus, self.D - (self.x + self.h * self.CosPsi2D), self.SinPsi2D) + + self.Crit[2]) / self.DeltaPhi + self.Jac[7] = 0.0 + self.Jac[8] = (self._YOffsetEqn(self.Y2Plus + self.DeltaY, self.D - (self.x + self.h * self.CosPsi2D), + self.SinPsi2) + self.Crit[2]) / self.DeltaY + + # solve for the next guess + + buildOutJac = self._moment(self.Y1Plus + self.DeltaY, self.Y2Plus, self.Phi, self.MySinPhi, self.SinPsi1, + self.CosPsi1, self.SinPsi2, self.CosPsi2) + self.Crit[0] + + self._MatSolv() # solves the matrix equation Jx=-Criterion + + # update the variables with the new estimate + + self.Phi = self.Phi + self.Solution[0] + self.Y1Plus = self.Y1Plus + self.Solution[1] # don't allow the anchor points to be inside a sprocket + if (self.Y1Plus < self.R): + self.Y1Plus = self.R + + self.Y2Plus = self.Y2Plus + self.Solution[2] # don't allow the anchor points to be inside a sprocke + if (self.Y2Plus < self.R): + self.Y2Plus = self.R + + self.Psi1 = self.Theta - self.Phi + self.Psi2 = self.Theta + self.Phi + + # evaluate the + # three criterion equations + self._MyTrig() + + self.Crit[0] = - self._moment(self.Y1Plus, self.Y2Plus, self.Phi, self.MySinPhi, self.SinPsi1, self.CosPsi1, + self.SinPsi2, self.CosPsi2) + self.Crit[1] = - self._YOffsetEqn(self.Y1Plus, self.x - self.h * self.CosPsi1, self.SinPsi1) + self.Crit[2] = - self._YOffsetEqn(self.Y2Plus, self.D - (self.x + self.h * self.CosPsi2), self.SinPsi2) + Tries = Tries + 1 # increment itteration count + + if (Tries > self.MaxTries): + print("unable to calculate chain lengths") + + # Variables are within accuracy limits + # perform output computation + + self.Offsetx1 = self.h * self.CosPsi1 + self.Offsetx2 = self.h * self.CosPsi2 + self.Offsety1 = self.h * self.SinPsi1 + self.Offsety2 = self.h * self.SinPsi2 + self.TanGamma = (self.y - self.Offsety1 + self.Y1Plus) / (self.x - self.Offsetx1) + self.TanLambda = (self.y - self.Offsety2 + self.Y2Plus) / (self.D - (self.x + self.Offsetx2)) + self.Gamma = math.atan(self.TanGamma) + self.Lambda = math.atan(self.TanLambda) + + # compute the chain lengths + + if (self.Mirror): + Chain2 = math.sqrt( + (self.x - self.Offsetx1) * (self.x - self.Offsetx1) + (self.y + self.Y1Plus - self.Offsety1) * ( + self.y + self.Y1Plus - self.Offsety1)) - self.R * self.TanGamma + self.R * self.Gamma # right chain length + Chain1 = math.sqrt((self.D - (self.x + self.Offsetx2)) * (self.D - (self.x + self.Offsetx2)) + ( + self.y + self.Y2Plus - self.Offsety2) * ( + self.y + self.Y2Plus - self.Offsety2)) - self.R * self.TanLambda + self.R * self.Lambda # left chain length + else: + Chain1 = math.sqrt( + (self.x - self.Offsetx1) * (self.x - self.Offsetx1) + (self.y + self.Y1Plus - self.Offsety1) * ( + self.y + self.Y1Plus - self.Offsety1)) - self.R * self.TanGamma + self.R * self.Gamma # left chain length + Chain2 = math.sqrt((self.D - (self.x + self.Offsetx2)) * (self.D - (self.x + self.Offsetx2)) + ( + self.y + self.Y2Plus - self.Offsety2) * ( + self.y + self.Y2Plus - self.Offsety2)) - self.R * self.TanLambda + self.R * self.Lambda # right chain length + + aChainLength = Chain1 + bChainLength = Chain2 + # print 'target ({:.2f},{:.2f}) chains {:.3f},{:.3f} chain diff {:.3f} sled angle {:.4f} (degrees{:.4f})'.format(xTarget,yTarget,aChainLength, bChainLength, aChainLength - bChainLength, self.Phi, self.Phi*3.14159) + + return aChainLength, bChainLength + + def forward(self, chainALength, chainBLength, xGuess = -10, yGuess = 10): + ''' + + Take the chain lengths and return an XY position + + ''' + # print("Chain Sag Correction:") + # print(self.chainSagCorrection) + # print("") + # apply any offsets for slipped links + chainALength = chainALength + (self.chain1Offset * self.R) + chainBLength = chainBLength + (self.chain2Offset * self.R) + + guessCount = 0 + + while (1): + + # check our guess + guessLengthA, guessLengthB = self.inverse(xGuess, yGuess) + + aChainError = chainALength - guessLengthA + bChainError = chainBLength - guessLengthB + + # print 'guess {:7.3f} {:7.3f} error {:7.3f} {:7.3f} guesslength {:7.3f} {:7.3f} '.format(xGuess,yGuess,aChainError,bChainError,guessLengthA, guessLengthB) + + # if we've converged on the point...or it's time to give up, exit the loop + if ((abs(aChainError) < .000000001 and abs(bChainError) < .000000001) or guessCount > 5000): + if (guessCount > 5000): + print + "Message: Unable to find valid machine position. Please calibrate chain lengths.", aChainError, bChainError, xGuess, yGuess + return xGuess, yGuess + else: + return xGuess, yGuess + else: + # adjust the guess based on the result + xGuess = xGuess + .1 * aChainError - .1 * bChainError + yGuess = yGuess - .1 * aChainError - .1 * bChainError + guessCount = guessCount + 1 + + def _MatSolv(self): + Sum = 0 + NN = 0 + i = 0 + ii = 0 + J = 0 + JJ = 0 + K = 0 + KK = 0 + L = 0 + M = 0 + N = 0 + + fact = 0 + + b = 0 + while b < 5: + b = b + 1 + + # gaus elimination, no pivot + + N = 3 + NN = N - 1 + i = 1 + while (i <= NN): + J = (N + 1 - i) + JJ = (J - 1) * N - 1 + L = J - 1 + KK = -1 + K = 0 + while (K < L): + fact = self.Jac[KK + J] / self.Jac[JJ + J]; + M = 1 + while (M <= J): + self.Jac[KK + M] = self.Jac[KK + M] - fact * self.Jac[JJ + M] + M = M + 1 + KK = KK + N; + self.Crit[K] = self.Crit[K] - fact * self.Crit[J - 1]; + K = K + 1 + i = i + 1 + + # Lower triangular matrix solver + + self.Solution[0] = self.Crit[0] / self.Jac[0] + ii = N - 1 + + i = 2 + while (i <= N): + M = i - 1; + Sum = self.Crit[i - 1]; + + J = 1 + while (J <= M): + Sum = Sum - self.Jac[ii + J] * self.Solution[J - 1]; + J = J + 1 + + self.Solution[i - 1] = Sum / self.Jac[ii + i]; + ii = ii + N; + + i = i + 1 + + def _moment(self, Y1Plus, Y2Plus, Phi, MSinPhi, MSinPsi1, MCosPsi1, MSinPsi2, + MCosPsi2): # computes net moment about center of mass + '''Temp + Offsetx1 + Offsetx2 + Offsety1 + Offsety2 + Psi1 + Psi2 + TanGamma + TanLambda''' + + self.Psi1 = self.Theta - Phi + self.Psi2 = self.Theta + Phi + + self.Offsetx1 = self.h * MCosPsi1 + self.Offsetx2 = self.h * MCosPsi2 + self.Offsety1 = self.h * MSinPsi1 + self.Offsety2 = self.h * MSinPsi2 + self.TanGamma = (self.y - self.Offsety1 + Y1Plus) / (self.x - self.Offsetx1) + self.TanLambda = (self.y - self.Offsety2 + Y2Plus) / (self.D - (self.x + self.Offsetx2)) + + return self.h3 * MSinPhi + (self.h / (self.TanLambda + self.TanGamma)) * ( + MSinPsi2 - MSinPsi1 + (self.TanGamma * MCosPsi1 - self.TanLambda * MCosPsi2)) + + def _MyTrig(self): + + Phisq = self.Phi * self.Phi + Phicu = self.Phi * Phisq + Phidel = self.Phi + self.DeltaPhi + Phidelsq = Phidel * Phidel + Phidelcu = Phidel * Phidelsq + Psi1sq = self.Psi1 * self.Psi1 + Psi1cu = Psi1sq * self.Psi1 + Psi2sq = self.Psi2 * self.Psi2 + Psi2cu = self.Psi2 * Psi2sq + Psi1del = self.Psi1 - self.DeltaPhi + Psi1delsq = Psi1del * Psi1del + Psi1delcu = Psi1del * Psi1delsq + Psi2del = self.Psi2 + self.DeltaPhi + Psi2delsq = Psi2del * Psi2del + Psi2delcu = Psi2del * Psi2delsq + + self.MySinPhi = -0.1616 * Phicu - 0.0021 * Phisq + 1.0002 * self.Phi + self.MySinPhiDelta = -0.1616 * Phidelcu - 0.0021 * Phidelsq + 1.0002 * Phidel + + self.SinPsi1 = -0.0942 * Psi1cu - 0.1368 * Psi1sq + 1.0965 * self.Psi1 - 0.0241 # sinPsi1 + self.CosPsi1 = 0.1369 * Psi1cu - 0.6799 * Psi1sq + 0.1077 * self.Psi1 + 0.9756 # cosPsi1 + self.SinPsi2 = -0.1460 * Psi2cu - 0.0197 * Psi2sq + 1.0068 * self.Psi2 - 0.0008 # sinPsi2 + self.CosPsi2 = 0.0792 * Psi2cu - 0.5559 * Psi2sq + 0.0171 * self.Psi2 + 0.9981 # cosPsi2 + + self.SinPsi1D = -0.0942 * Psi1delcu - 0.1368 * Psi1delsq + 1.0965 * Psi1del - 0.0241 # sinPsi1 + self.CosPsi1D = 0.1369 * Psi1delcu - 0.6799 * Psi1delsq + 0.1077 * Psi1del + 0.9756 # cosPsi1 + self.SinPsi2D = -0.1460 * Psi2delcu - 0.0197 * Psi2delsq + 1.0068 * Psi2del - 0.0008 # sinPsi2 + self.CosPsi2D = 0.0792 * Psi2delcu - 0.5559 * Psi2delsq + 0.0171 * Psi2del + 0.9981 # cosPsi2 + + def _YOffsetEqn(self, YPlus, Denominator, Psi): + + Temp = ((math.sqrt(YPlus * YPlus - self.R * self.R) / self.R) - ( + self.y + YPlus - self.h * math.sin(Psi)) / Denominator) + return Temp + + def updateSetting(self, firmwareKey, value): + + if firmwareKey == 2: + self.D = float(value) + elif firmwareKey == 13: + self.R = float(value/3.141592/2) + elif firmwareKey == 1: + self.machineHeight = float(value) + elif firmwareKey == 0: + self.machineWidth = float(value) + elif firmwareKey == 3: + self.motorOffsetY = float(value) + elif firmwareKey == 40: + self.leftChainTolerance = float(value) + elif firmwareKey == 41: + self.rightChainTolerance = float(value) + elif firmwareKey == 45: + self.chainElasticity = float(value) + elif firmwareKey == 46: + self.sledWeight = float(value) + elif firmwareKey == 8: + self.rotationDiskRadius = float(value) + elif firmwareKey == 37: + self.chainSagCorrection = float(value) + elif firmwareKey == 38: + self.chainOverSprocket = int(value) + elif firmwareKey == 7: + if int(value) == 1: + self.isQuadKinematics = True + else: + self.isQuadKinematics = False + self._xCordOfMotor = self.D / 2 + self._yCordOfMotor = self.machineHeight / 2 + self.motorOffsetY + + def initializeSettings(self): + self.D = float(self.data.config.getValue("Maslow Settings","motorSpacingX")) + self.R = float(self.data.config.getValue("Computed Settings","distPerRot"))/3.141592/2 + self.machineHeight = float(self.data.config.getValue("Maslow Settings","bedHeight")) + self.machineWidth = float(self.data.config.getValue("Maslow Settings", "bedWidth")) + self.motorOffsetY = float(self.data.config.getValue("Maslow Settings", "motorOffsetY")) + self.leftChainTolerance = float(self.data.config.getValue("Advanced Settings", "leftChainTolerance")) + self.rightChainTolerance = float(self.data.config.getValue("Advanced Settings", "rightChainTolerance")) + self.chainElasticity = float(self.data.config.getValue("Advanced Settings", "chainElasticity")) + self.sledWeight = float(self.data.config.getValue("Maslow Settings", "sledWeight")) + self.rotationDiskRadius = float(self.data.config.getValue("Advanced Settings", "rotationRadius")) + self.chainSagCorrection = float(self.data.config.getValue("Advanced Settings", "chainSagCorrection")) + self.chainOverSprocket = int(self.data.config.getValue("Computed Settings", "chainOverSprocketComputed")) + kinematicsType = int(self.data.config.getValue("Computed Settings", "kinematicsTypeComputed")) + if kinematicsType == 1: + self.isQuadKinematics = True + else: + self.isQuadKinematics = False + + + diff --git a/Actions/actions.py b/Actions/actions.py index eb78df5b..33561e2a 100644 --- a/Actions/actions.py +++ b/Actions/actions.py @@ -1,209 +1,536 @@ + from DataStructures.makesmithInitFuncs import MakesmithInitFuncs +import os import sys -import threading -import re import math import serial.tools.list_ports import glob import json +import time +import re +import zipfile +import threading +import platform +from subprocess import call +from gpiozero.pins.mock import MockFactory +from gpiozero import Device - +''' +This class does most of the heavy lifting in processing messages from the UI client. +''' class Actions(MakesmithInitFuncs): + + Device.pin_factory = MockFactory() + def processAction(self, msg): - if msg["data"]["command"] == "resetChainLengths": - if not self.resetChainLengths(): - self.data.ui_queue.put("Message: Error with resetting chain lengths.") - elif msg["data"]["command"] == "reportSettings": - self.data.gcode_queue.put("$$") - elif msg["data"]["command"] == "home": - if not self.home(): - self.data.ui_queue.put("Message: Error with returning to home.") - elif msg["data"]["command"] == "defineHome": - if self.defineHome(): - ## the gcode file might change the active units so we need to inform the UI of the change. - self.data.ui_queue.put("Action: unitsUpdate gcodeUpdate") - else: - self.data.ui_queue.put("Message: Error with defining home.") - elif msg["data"]["command"] == "defineZ0": - if not self.data.actions.defineZ0(): - self.data.ui_queue.put("Message: Error with defining Z-Axis zero.") - elif msg["data"]["command"] == "stopZ": - if not self.stopZ(): - self.data.ui_queue.put("Message: Error with stopping Z-Axis movement") - elif msg["data"]["command"] == "startRun": - if not self.startRun(): - self.data.ui_queue.put("Message: Error with starting run") - elif msg["data"]["command"] == "stopRun": - if not self.stopRun(): - self.data.ui_queue.put("Message: Error with stopping run") - elif msg["data"]["command"] == "moveToDefault": - if not self.moveToDefault(): - self.data.ui_queue.put( - "Message: Error with moving to default chain lengths" - ) - elif msg["data"]["command"] == "testMotors": - if not self.testMotors(): - self.data.ui_queue.put("Message: Error with testing motors") - elif msg["data"]["command"] == "wipeEEPROM": - if not self.wipeEEPROM(): - self.data.ui_queue.put("Message: Error with wiping EEPROM") - elif msg["data"]["command"] == "pauseRun": - if not self.pauseRun(): - self.data.ui_queue.put("Message: Error with pausing run") - elif msg["data"]["command"] == "resumeRun": - if not self.resumeRun(): - self.data.ui_queue.put("Message: Error with resuming run") - elif msg["data"]["command"] == "returnToCenter": - if not self.returnToCenter(): - self.data.ui_queue.put("Message: Error with returning to center") - elif msg["data"]["command"] == "clearGCode": - if self.clearGCode(): - # send blank gcode to UI - self.data.ui_queue.put("Action: gcodeUpdate") - # socketio.emit("gcodeUpdate", {"data": ""}, namespace="/MaslowCNC") + ''' + When a message comes in via the UI client it gets parsed and processed here. + :param msg: json of message from UI client + :return: + ''' + ''' + if msg["data"]["command"] == "optimizeGCode": + if not self.data.gcodeOptimizer.optimize(): + self.data.ui_queue1.put("Alert", "Alert", "Error with optimizing gcode") + ''' + try: + # Commands allowed during sending gcode. These commands won't screw something up. + if msg["data"]["command"] == "createDirectory": + if not self.createDirectory(msg["data"]["arg"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with creating directory.") + elif msg["data"]["command"] == "stopZ": + if not self.stopZ(): + self.data.ui_queue1.put("Alert", "Alert", "Error with stopping Z-Axis movement") + elif msg["data"]["command"] == "stopRun": + if not self.stopRun(): + self.data.ui_queue1.put("Alert", "Alert", "Error with stopping run") + elif msg["data"]["command"] == "pauseRun": + if not self.pauseRun(): + self.data.ui_queue1.put("Alert", "Alert", "Error with pausing run") + elif msg["data"]["command"] == "resumeRun": + if not self.resumeRun(): + self.data.ui_queue1.put("Alert", "Alert", "Error with resuming run") + elif msg["data"]["command"] == "toggleCamera": + if not self.toggleCamera(): + self.data.ui_queue1.put("Alert", "Alert", "Error with toggling camera.") + elif msg["data"]["command"] == "statusRequest": + if msg["data"]["arg"] == "cameraStatus": + if not self.cameraStatus(): + self.data.ui_queue1.put("Alert", "Alert", "Error with toggling camera.") + elif msg["data"]["command"] == "queryCamera": + if not self.queryCamera(): + self.data.ui_queue1.put("Alert", "Alert", "Error with querying camera.") + elif msg["data"]["command"] == "shutdown": + if not self.shutdown(): + self.data.ui_queue1.put("Alert", "Alert", "Error with shutting down.") + elif msg["data"]["command"] == "TurnOffRPI": + if not self.turnOff(): + self.data.ui_queue1.put("Alert", "Alert", "Error with system shutting down.") + elif self.data.uploadFlag == 1: + self.data.ui_queue1.put("Alert", "Alert", "Cannot issue command while sending gcode.") + # Commands not allowed during sending gcode.. if you did these commands, something could screw up. + # If uploadFlag was enabled (see above) then this would never be reached. + + elif msg["data"]["command"] == "move": + if not self.move(msg["data"]["arg"], float(msg["data"]["arg1"])): + self.data.ui_queue1.put("Alert", "Alert", "Error with initiating move.") + elif msg["data"]["command"] == "moveTo": + if not self.moveTo(msg["data"]["arg"], float(msg["data"]["arg1"])): + self.data.ui_queue1.put("Alert", "Alert", "Error with initiating move.") + elif msg["data"]["command"] == "moveZ": + if not self.moveZ(msg["data"]["arg"], float(msg["data"]["arg1"])): + self.data.ui_queue1.put("Alert", "Alert", "Error with initiating Z-Axis move.") + elif msg["data"]["command"] == "reportSettings": + self.data.gcode_queue.put("$$") + elif msg["data"]["command"] == "home": + if not self.home(): + self.data.ui_queue1.put("Alert", "Alert", "Error with returning to home.") + elif msg["data"]["command"] == "defineZ0": + if not self.data.actions.defineZ0(): + self.data.ui_queue1.put("Alert", "Alert", "Error with defining Z-Axis zero.") + elif msg["data"]["command"] == "touchZ": + if not self.touchZ(): + self.data.ui_queue1.put("Alert", "Alert", "Error with touching.") + elif msg["data"]["command"] == "moveToDefault": + if not self.moveToDefault(): + self.data.ui_queue1.put("Alert", "Alert", "Error with moving to default chain lengths") + elif msg["data"]["command"] == "returnToCenter": + if not self.returnToCenter(): + self.data.ui_queue1.put("Alert", "Alert", "Error with returning to center") + elif msg["data"]["command"] == "moveGcodeZ": + if not self.moveGcodeZ(int(msg["data"]["arg"])): + self.data.ui_queue1.put("Alert", "Alert", "Error with moving to Z move") + elif msg["data"]["command"] == "moveGcodeGoto": + if not self.moveGcodeIndex(int(msg["data"]["arg"]), True): + self.data.ui_queue1.put("Alert", "Alert", "Error with moving to Z move") + elif msg["data"]["command"] == "moveGcodeIndex": + if not self.moveGcodeIndex(int(msg["data"]["arg"])): + self.data.ui_queue1.put("Alert", "Alert", "Error with moving to index") + elif msg["data"]["command"] == "macro1": + if not self.macro(1): + self.data.ui_queue1.put("Alert", "Alert", "Error with performing macro") + elif msg["data"]["command"] == "macro2": + if not self.macro(2): + self.data.ui_queue1.put("Alert", "Alert", "Error with performing macro") + elif msg["data"]["command"] == "clearLogs": + if not self.clearLogs(): + self.data.ui_queue1.put("Alert", "Alert", "Error clearing log files.") + + elif self.data.uploadFlag > 1 or self.data.uploadFlag < 0 : + self.data.ui_queue1.put("Alert", "Alert", "Cannot issue command while paused sending gcode. You must press STOP before performing this action.") + # Commands not allowed while paused.. if you did these commands, something could screw up. + + elif msg["data"]["command"] == "startRun": + if not self.startRun(): + if len(self.data.gcode) > 0: + self.data.ui_queue1.put("Alert", "Alert", "Error with starting run.") + else: + self.data.ui_queue1.put("Alert", "Alert", "No GCode file loaded.") + elif msg["data"]["command"] == "update": + if not self.data.releaseManager.update(msg["data"]["arg"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with updating webcontrol.") + return "Shutdown" + elif msg["data"]["command"] == "cutTriangularCalibrationPattern": + if not self.data.triangularCalibration.cutTriangularCalibrationPattern(): + self.data.ui_queue1.put("Alert", "Alert", "Error with cutting triangular calibration pattern.") + elif msg["data"]["command"] == "acceptTriangularCalibrationResults": + if not self.data.triangularCalibration.acceptTriangularCalibrationResults(): + self.data.ui_queue1.put("Alert", "Alert", "Error with accepting triangular calibration results.") + elif msg["data"]["command"] == "cutHoleyCalibrationPattern": + if not self.data.holeyCalibration.CutTestPattern(): + self.data.ui_queue1.put("Alert", "Alert", "Error with cutting holey calibration pattern.") + elif msg["data"]["command"] == "acceptHoleyCalibrationResults": + if not self.data.holeyCalibration.acceptCalibrationResults(): + self.data.ui_queue1.put("Alert", "Alert", "Error with accepting holey calibration results.") + elif msg["data"]["command"] == "resetChainLengths": + if not self.resetChainLengths(): + self.data.ui_queue1.put("Alert", "Alert", "Error with resetting chain lengths.") + elif msg["data"]["command"] == "defineHome": + print(self.data.uploadFlag) + posX= msg["data"]["arg"] + posY= msg["data"]["arg1"] + if self.defineHome(posX, posY): + ## the gcode file might change the active units so we need to inform the UI of the change. + self.data.ui_queue1.put("Action", "unitsUpdate", "") + self.data.ui_queue1.put("Action", "gcodeUpdate", "") + else: + self.data.ui_queue1.put("Alert", "Alert", "Error with defining home.") + elif msg["data"]["command"] == "testMotors": + if not self.testMotors(): + self.data.ui_queue1.put("Alert", "Alert", "Error with testing motors") + elif msg["data"]["command"] == "wipeEEPROM": + if not self.wipeEEPROM(msg["data"]["arg"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with wiping EEPROM") + elif msg["data"]["command"] == "clearGCode": + if self.clearGCode(): + # send blank gcode to UI + self.data.ui_queue1.put("Action", "gcodeUpdate", "") + else: + self.data.ui_queue1.put("Alert", "Alert", "Error with clearing gcode") + elif msg["data"]["command"] == "setSprockets": + if not self.setSprockets(msg["data"]["arg"], msg["data"]["arg1"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with setting sprocket") + elif msg["data"]["command"] == "rotateSprocket": + if not self.rotateSprocket(msg["data"]["arg"], msg["data"]["arg1"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with setting sprocket") + elif msg["data"]["command"] == "setSprocketAutomatic": + if not self.setSprocketAutomatic(): + self.data.ui_queue1.put("Alert", "Alert", "Error with setting sprockets automatically") + elif msg["data"]["command"] == "setSprocketsZero": + if not self.setSprocketsZero(): + self.data.ui_queue1.put("Alert", "Alert", "Error with setting sprockets zero value") + elif msg["data"]["command"] == "setSprocketsDefault": + if not self.setSprocketsDefault(): + self.data.ui_queue1.put("Alert", "Alert", "Error with setting sprockets as default") + elif msg["data"]["command"] == "updatePorts": + if not self.updatePorts(): + self.data.ui_queue1.put("Alert", "Alert", "Error with updating list of ports") + elif msg["data"]["command"] == "optical_onStart": + pass + #if not self.data.opticalCalibration.on_Start(): + # self.data.ui_queue1.put("Alert", "Alert", "Error with starting optical calibration") + elif msg["data"]["command"] == "optical_Calibrate": + pass + #if not self.data.opticalCalibration.on_Calibrate(msg["data"]["arg"]): + # self.data.ui_queue1.put("Alert", "Alert", "Error with starting optical calibration") + elif msg["data"]["command"] == "saveOpticalCalibrationConfiguration": + pass + #if not self.data.opticalCalibration.saveOpticalCalibrationConfiguration(msg["data"]["arg"]): + # self.data.ui_queue1.put("Alert", "Alert", "Error with saving optical calibration configuration") + elif msg["data"]["command"] == "stopOpticalCalibration": + pass + #if not self.data.opticalCalibration.stopOpticalCalibration(): + # self.data.ui_queue1.put("Alert", "Alert", "Error with stopping optical calibration.") + elif msg["data"]["command"] == "testOpticalCalibration": + pass + #if not self.data.opticalCalibration.testImage(msg["data"]["arg"]): + # self.data.ui_queue1.put("Alert", "Alert", "Error with test image.") + elif msg["data"]["command"] == "findCenterOpticalCalibration": + pass + #if not self.data.opticalCalibration.findCenter(msg["data"]["arg"]): + # self.data.ui_queue1.put("Alert", "Alert", "Error with find Center.") + elif msg["data"]["command"] == "saveAndSendOpticalCalibration": + pass + #if not self.data.opticalCalibration.saveAndSend(): + # self.data.ui_queue1.put("Alert", "Alert", "Error with saving and sending calibration matrix.") + elif msg["data"]["command"] == "reloadCalibration": + pass + ''' + errorX, errorY, curveX, curveY = self.data.opticalCalibration.reloadCalibration() + if errorX is None or errorY is None or curveX is None or curveY is None: + self.data.ui_queue1.put("Alert", "Alert", "Error with (re)loading calibration.") + else: + data = {"errorX": errorX, "errorY": errorY} + self.data.ui_queue1.put("Action", "updateOpticalCalibrationError", data) + ''' + elif msg["data"]["command"] == "saveCalibrationToCSV": + pass + #if not self.data.opticalCalibration.saveCalibrationToCSV(): + # self.data.ui_queue1.put("Alert", "Alert", "Error with saving calibration to CSV.") + elif msg["data"]["command"] == "clearCalibration": + pass + #if not self.data.opticalCalibration.clearCalibration(): + # self.data.ui_queue1.put("Alert", "Alert", "Error with clearing calibration.") + elif msg["data"]["command"] == "curveFitOpticalCalibration": + pass + ''' + curveX, curveY = self.data.opticalCalibration.surfaceFit() + #curveX, curveY = self.data.opticalCalibration.polySurfaceFit() + if curveX is None or curveY is None: + self.data.ui_queue1.put("Alert", "Alert", "Error with curve fitting calibration data.") + else: + data = {"curveX": curveX, "curveY": curveY} + self.data.ui_queue1.put("Action", "updateOpticalCalibrationCurve", data) + ''' + elif msg["data"]["command"] == "adjustCenter": + if not self.adjustCenter(msg["data"]["arg"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with adjusting center.") + elif msg["data"]["command"] == "upgradeCustomFirmware": + if not self.upgradeFirmware(0): + self.data.ui_queue1.put("Alert", "Alert", "Error with upgrading custom firmware.") + else: + self.data.ui_queue1.put("Alert", "Alert", "Custom firmware update complete.") + elif msg["data"]["command"] == "upgradeStockFirmware": + if not self.upgradeFirmware(1): + self.data.ui_queue1.put("Alert", "Alert", "Error with upgrading stock firmware.") + else: + self.data.ui_queue1.put("Alert", "Alert", "Stock firmware update complete.") + elif msg["data"]["command"] == "upgradeHoleyFirmware": + if not self.upgradeFirmware(2): + self.data.ui_queue1.put("Alert", "Alert", "Error with upgrading holey firmware.") + else: + self.data.ui_queue1.put("Alert", "Alert", "Custom firmware update complete.") + elif msg["data"]["command"] == "adjustChain": + if not self.adjustChain(msg["data"]["arg"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with adjusting chain.") + elif msg["data"]["command"] == "executeVelocityPIDTest": + if not self.velocityPIDTest(msg["data"]["arg"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with executing velocity PID test.") + elif msg["data"]["command"] == "executePositionPIDTest": + if not self.positionPIDTest(msg["data"]["arg"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with executing velocity PID test.") + elif msg["data"]["command"] == "boardProcessGCode": + if not self.data.boardManager.processGCode(): + self.data.ui_queue1.put("Alert", "Alert", "Error with processing gcode") + elif msg["data"]["command"] == "boardClearBoard": + if not self.data.boardManager.clearBoard(): + self.data.ui_queue1.put("Alert", "Alert", "Error with clearing board") + elif msg["data"]["command"] == "updatePyInstaller": + if not self.data.releaseManager.updatePyInstaller(): + self.data.ui_queue1.put("Alert", "Alert", "Error with updating WebControl") + return "Shutdown" + elif msg["data"]["command"] == "setFakeServo": + if not self.setFakeServo(msg["data"]["arg"]): + self.data.ui_queue1.put("Alert", "Alert", "Error with changing Fake Servo") + elif msg["data"]["command"] == "resetHomeToCenter": + if self.defineHome(0, 0): + ## notify UI of home change to request gcode update + self.data.ui_queue1.put("Action", "gcodeUpdate", "") + else: + self.data.ui_queue1.put("Alert", "Alert", "Error with resetting home to center") + #elif msg["data"]["command"] == "optimizeGCode": + # if not self.data.gcodeOptimizer.optimize(): + # self.data.ui_queue1.put("Alert", "Alert", "Error with optimizing gcode") else: - self.data.ui_queue.put("Message: Error with clearing gcode") - elif msg["data"]["command"] == "moveGcodeZ": - if not self.moveGcodeZ(int(msg["data"]["arg"])): - self.data.ui_queue.put("Message: Error with moving to Z move") - elif ( - msg["data"]["command"] == "moveGcodeIndex" - or msg["data"]["command"] == "moveGcodeZ" - ): - if not self.moveGcodeIndex(int(msg["data"]["arg"])): - self.data.ui_queue.put("Message: Error with moving to index") - elif msg["data"]["command"] == "setSprockets": - if not self.setSprockets(msg["data"]["arg"], msg["data"]["arg1"]): - self.data.ui_queue.put("Message: Error with setting sprocket") - elif msg["data"]["command"] == "setSprocketsAutomatic": - if not self.setSprocketsAutomatic(): - self.data.ui_queue.put( - "Message: Error with setting sprockets automatically" - ) - elif msg["data"]["command"] == "setSprocketsZero": - if not self.setSprocketsZero(): - self.data.ui_queue.put( - "Message: Error with setting sprockets zero value" - ) - elif msg["data"]["command"] == "updatePorts": - if not self.updatePorts(): - self.data.ui_queue.put("Message: Error with updating list of ports") - elif msg["data"]["command"] == "macro1": - if not self.macro(1): - self.data.ui_queue.put("Message: Error with performing macro") - elif msg["data"]["command"] == "macro2": - if not self.macro(2): - self.data.ui_queue.put("Message: Error with performing macro") - elif msg["data"]["command"] == "optical_onStart": - if not self.data.opticalCalibration.on_Start(): - self.data.ui_queue.put( - "Message: Error with starting optical calibration" - ) - elif msg["data"]["command"] == "optical_Calibrate": - print("here") - if not self.data.opticalCalibration.on_Calibrate(msg["data"]["arg"]): - self.data.ui_queue.put( - "Message: Error with starting optical calibration" - ) + response = "Function not currently implemented.. Sorry." + response = response + "["+msg["data"]["command"]+"]" + self.data.ui_queue1.put("Alert", "Alert", response) + print(msg["data"]) + except Exception as e: + print(str(e)) + - def defineHome(self): + def shutdown(self): + ''' + If running docker, sends message to WebMCP to shutdown webcontrol. + If running as pyinstaller, calls an exit function. + TODO: Add option to shutdown RPI completely. + :return: + ''' + try: + print(self.data.platform) + if self.data.platform == "PYINSTALLER": + os._exit(0) + else: + self.data.ui_queue1.put("WebMCP", "shutdown", "") + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def turnOff(self): + ''' this is the rpi soft power button function''' + try: + oname = os.name + print ("OS is ", oname) + if oname == "posix": + print(os.system("uname -a")) + # insert other possible OSes here + # ... NEED ARE YOU SURE YOU WANT POWER DOWN? + call("sudo --non-interactive shutdown -h now", shell=True) + return(True) #this should never run + else: + print("unknown OS") + print(self.data.platform) + #print(os.uname) + return(False) + except: + print("shutdown failure") + return(False) + + def defineHome(self, posX="", posY=""): + ''' + Redefines the home location and sends message to update the UI client. In a break from ground control, this + does not alter the gcode. Gcode is altered by the home location only when sent to the controller. + posX and posY define the coordinates of home. The are populated via the right-click context menu if the user + uses the mouse to define home. They are empty if the user presses the define home button on the frontpage + menu, in which case the coordinates of the sled are used. + :param posX: + :param posY: + :return: + ''' try: if self.data.units == "MM": scaleFactor = 25.4 else: scaleFactor = 1.0 - self.data.gcodeShift = [ - self.data.xval / scaleFactor, - self.data.yval / scaleFactor, - ] - self.data.config.setValue("Advanced Settings", "homeX", str(self.data.xval)) - self.data.config.setValue("Advanced Settings", "homeY", str(self.data.yval)) - self.data.gcodeFile.loadUpdateFile() + # if posX and posY have values, use them, else use the sled's position. + if posX != "" and posY != "": + homeX = round(posX * scaleFactor, 4) + homeY = round(posY * scaleFactor, 4) + else: + homeX = round(self.data.xval, 4) + homeY = round(self.data.yval, 4) + + self.data.config.setValue("Advanced Settings", "homeX", str(homeX)) + self.data.config.setValue("Advanced Settings", "homeY", str(homeY)) + + # the moveLine function of gcodeFile is still used (though its called directly by serialThread) so I still + # track the home coordinates in gcodeShift. + self.data.gcodeShift = [ homeX, homeY ] + # send update to UI client with new home position + position = {"xval": homeX, "yval": homeY} + self.data.ui_queue1.put("Action", "homePositionMessage", position) return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def home(self): + ''' + Directs controller to move to home location + :return: + ''' try: + self.data.sledMoving = True self.data.gcode_queue.put("G90 ") - # todo:self.gcodeVel = "[MAN]" safeHeightMM = float( self.data.config.getValue("Maslow Settings", "zAxisSafeHeight") ) - safeHeightInches = safeHeightMM / 25.5 + safeHeightInches = safeHeightMM / 25.4 if self.data.units == "INCHES": self.data.gcode_queue.put("G00 Z" + "%.3f" % (safeHeightInches)) else: self.data.gcode_queue.put("G00 Z" + str(safeHeightMM)) + homeX = self.data.config.getValue("Advanced Settings", "homeX") + homeY = self.data.config.getValue("Advanced Settings", "homeY") self.data.gcode_queue.put( "G00 X" - + str(self.data.gcodeShift[0]) + + str(homeX) + " Y" - + str(self.data.gcodeShift[1]) + + str(homeY) + " " ) self.data.gcode_queue.put("G00 Z0 ") + self.data.sledMoving = False return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) + self.data.sledMoving = False return False def resetChainLengths(self): + ''' + Sends B08 command to controller to tell controller chains are at their 'extendChainLengths' distance. + (equivalent to ground control's manualCalibrateChainLengths function) + :return: + ''' try: self.data.gcode_queue.put("B08 ") + # not sure why this was added here. Probably not needed. Todo: cleanup if not needed. + if self.data.units == "INCHES": + self.data.gcode_queue.put("G20 ") + else: + self.data.gcode_queue.put("G21 ") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def defineZ0(self): + ''' + Sends G10 Z0 to controller to set current Z height as zero. + :return: + ''' try: self.data.gcode_queue.put("G10 Z0 ") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def stopZ(self): + ''' + Sends a stop signal to the controller and clears the gcode queue. This is called from the Z-Axis popup, not + the frontpage. This is equivalent to ground control's stopZMove. + :return: + ''' try: + print("z!") self.data.quick_queue.put("!") with self.data.gcode_queue.mutex: self.data.gcode_queue.queue.clear() + self.data.Zmoving = False return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def startRun(self): + ''' + Starts the process of sending the gcode to the controller. + :return: + ''' try: - self.data.uploadFlag = 1 - self.data.gcode_queue.put(self.data.gcode[self.data.gcodeIndex]) - self.data.gcodeIndex += 1 - return True + if len(self.data.gcode) > 0: + # set current Z target to the current z height in case gcode doesn't include a z move before an xy move. + # if it doesn't and the user pauses during an xy move, then the target Z is set to 0. This sets it to + # what it currently is when the user started the gcode send. + self.data.currentZTarget = self.data.zval + # if the gcode index is not 0, then make sure the machine is in the proper state before starting to send + # the gcode. + if self.data.gcodeIndex > 0: + # get machine into proper state by sending appropriate commands + self.processGCode() + # update the gcode position on the UI client.. Have to recalculate it from the gcode because + # starting at some place other than 0 + self.sendGCodePositionUpdate(recalculate=True) + self.data.uploadFlag = 1 + else: + self.data.uploadFlag = 1 + if (self.data.GPIOButtonService == False): + self.data.gpioActions.causeAction("PlayLED", "on") + return True + else: + return False except Exception as e: - print(e) + # something goes wrong, stop uploading. + self.data.console_queue.put(str(e)) self.data.uploadFlag = 0 self.data.gcodeIndex = 0 return False def stopRun(self): + ''' + Stops the uploading of gcode. + :return: + ''' + print("stopping run") try: - print("trying to stop run") + self.data.console_queue.put("stopping run") + # this is necessary because of the way PID data is being processed. Otherwise could potentially get stuck + # in PID test + self.data.inPIDPositionTest = False + self.data.inPIDVelocityTest = False self.data.uploadFlag = 0 self.data.gcodeIndex = 0 + self.data.manualZAxisAdjust = False self.data.quick_queue.put("!") with self.data.gcode_queue.mutex: self.data.gcode_queue.queue.clear() - # TODO: app.onUploadFlagChange(self.stopRun, 0) - print("Gcode Stopped") + # TODO: app.onUploadFlagChange(self.stopRun, 0) edit: not sure this is needed anymore + self.data.console_queue.put("Gcode stopped") + self.sendGCodePositionUpdate(self.data.gcodeIndex) + # notify UI client to clear any alarm that's active because a stop has been process. + self.data.ui_queue1.put("Action", "clearAlarm", "") + if (self.data.GPIOButtonService == False): + self.data.gpioActions.causeAction("StopLED", "on") + # reset pause + self.data.ui_queue1.put("Action", "setAsPause", "") + if (self.data.GPIOButtonService == False): + self.data.gpioActions.causeAction("PauseLED", "off") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def moveToDefault(self): + ''' + Moves the sled to the spot where the chains are extended to the extendChainLength. Not regularly used, but + more for testing. Uses B09 commands (single axis moves). + :return: + ''' try: chainLength = self.data.config.getValue( "Advanced Settings", "chainExtendLength" @@ -213,51 +540,161 @@ def moveToDefault(self): "B09 R" + str(chainLength) + " L" + str(chainLength) + " " ) self.data.gcode_queue.put("G91 ") + + # the firmware doesn't update sys.xPosition or sys.yPosition during a singleAxisMove + # therefore, the machine doesn't know where it is. + # so tell the machine where it's at by sending a reset chain length + self.data.gcode_queue.put("B08 ") + return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def testMotors(self): + ''' + Sends the test motors/encoder command, B04 + :return: + ''' try: self.data.gcode_queue.put("B04 ") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False - def wipeEEPROM(self): + def wipeEEPROM(self, extent): + ''' + Sends the wipe EEPROM commands + :param extent: + :return: + ''' try: - self.data.gcode_queue.put("$RST=* ") - timer = threading.Timer(6.0, self.data.gcode_queue.put("$$")) - timer.start() + if extent == "All": + self.data.gcode_queue.put("$RST=* ") + elif extent == "Settings": + self.data.gcode_queue.put("$RST=$ ") + elif extent == "Maslow": + self.data.gcode_queue.put("$RST=# ") + else: + return False + + #sync settings after 2 seconds (give time form controller to reset) + time.sleep(2) + self.data.gcode_queue.put("$$") + + #reset chain lengths so they aren't zero + if extent == "All" or extent == "Maslow": + self.resetChainLengths() + + # these two lines were commented out and aren't used (and may not even work). The thought was that after + # the EEPROM got wiped, you need to sync settings. + #self.timer = threading.Timer(6.0, self.data.gcode_queue.put("$$")) + #self.timer.start() return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def pauseRun(self): + ''' + Pause the current uploading of gcode. Notify UI client to change the Pause button to say Resume + :return: + ''' + print("pause run selected") try: - self.data.uploadFlag = 0 - print("Run Paused") - self.data.ui_queue.put("Action: setAsResume") + if self.data.uploadFlag == 1: + self.data.uploadFlag = 2 + self.data.console_queue.put("Run Paused") + self.data.ui_queue1.put("Action", "setAsResume", "") + # The idea was to be able to make sure the machine returns to + # the correct z-height after a pause in the event the user raised/lowered the bit. + #self.data.pausedzval = self.data.zval + #self.data.pausedUnits = self.data.units + self.data.pausedzval = self.data.currentZTarget + self.data.pausedUnits = self.data.units + self.data.pausedPositioningMode = self.data.positioningMode + #print("Saving paused positioning mode: " + str(self.data.pausedPositioningMode)) + if (self.data.GPIOButtonService == False): + self.data.gpioActions.causeAction("PauseLED", "on") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def resumeRun(self): + ''' + Resumes sending the gcode. If a tool change command was received, then the manualZAxisAdjust is enabled and + the machine will be returned to the z-axis height it was when the tool change command was processed. It also + makes sure the units are what they were prior to the tool change (user might have switched them up while + setting z-axis to zero). + :return: + ''' try: - self.data.uploadFlag = 1 - # send cycle resume command to unpause the machine + # Restore self.data.upladFlag properly + if self.data.manualZAxisAdjust: + # Z-axis is disabled and requires manual adjustment. + print("Resume run with manual z-axis adjust.") + # Clear the flag. + self.data.manualZAxisAdjust = False + # Reenable the uploadFlag if it was previous set. + if self.data.previousUploadStatus == -1: + # If this was M command pause, then set to 1. + self.data.uploadFlag = 1 + else: + self.data.uploadFlag = self.data.previousUploadStatus ### just moved this here from after if statement + else: + # User has paused and is now resuming. + # User could have used UI to move z-axis so restore paused values. + print("Resume run without manual z-axis adjust.") + # Restore units. + if self.data.pausedUnits is not None and self.data.pausedUnits != self.data.units: + print("Restoring units to:" + str(self.data.pausedUnits)) + if self.data.pausedUnits == "INCHES": + self.data.gcode_queue.put("G20 ") + elif self.data.pausedUnits == "MM": + self.data.gcode_queue.put("G21 ") + self.data.pausedUnits = None + + # Move the z-axis back to where it was. + if self.data.pausedzval is not None and self.data.pausedzval != self.data.zval: + # Put in absolute mode to make z axis move. + self.data.gcode_queue.put("G90 ") + # THE ABOVE COMMAND IS NOT EXECUTED IN LINE AND REQUIRES THE FOLLOWING TO TRACK POSITIONING MODE + self.data.positioningMode = 0 + print("Restoring paused Z value: " + str(self.data.pausedzval)) + self.data.gcode_queue.put("G0 Z" + str(self.data.pausedzval) + " ") + self.data.pausedzval = None + + # Restore the last gcode positioning mode in use before pauseRun executed. + if self.data.pausedPositioningMode is not None and self.data.positioningMode != self.data.pausedPositioningMode: + print("Restoring positioning mode: " + str(self.data.pausedPositioningMode)) + if self.data.pausedPositioningMode == 0: + # this line technically should be unreachable + self.data.gcode_queue.put("G90 ") + elif self.data.pausedPositioningMode == 1: + self.data.gcode_queue.put("G91 ") + self.data.pausedPositioningMode = None + + self.sendGCodePositionUpdate(self.data.gcodeIndex, recalculate=True) + self.data.uploadFlag = 1 + + # Send cycle resume command to unpause the machine. + # Only needed if user initiated pause; but doesn't actually cause harm to controller. self.data.quick_queue.put("~") - self.data.ui_queue.put("Action: setAsPause") + self.data.ui_queue1.put("Action", "setAsPause", "") + if (self.data.GPIOButtonService == False): + self.data.gpioActions.causeAction("PauseLED", "off") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def returnToCenter(self): + ''' + Instructs controller to move sled to 0,0 at safe height. + :return: + ''' try: self.data.gcode_queue.put("G90 ") safeHeightMM = float( @@ -271,20 +708,30 @@ def returnToCenter(self): self.data.gcode_queue.put("G00 X0.0 Y0.0 ") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def clearGCode(self): + ''' + Calls function to clear the gcode file. Probably could have just been called directly from processAction + :return: + ''' try: - self.data.gcodeFile = "" + self.data.gcodeFile.clearGcodeFile() return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def moveGcodeZ(self, moves): + ''' + Moves the gcode index to the next z-axis move. + :param moves: + :return: + ''' try: dist = 0 + #determine the number of lines to move to reach the next Z-axis move. for index, zMove in enumerate(self.data.zMoves): if moves > 0 and zMove > self.data.gcodeIndex: dist = self.data.zMoves[index + moves - 1] - self.data.gcodeIndex @@ -297,15 +744,23 @@ def moveGcodeZ(self, moves): else: return False except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False - def moveGcodeIndex(self, dist): + def moveGcodeIndex(self, dist, index=False): + ''' + Moves the gcodeIndex by either the distance or, in index is True, uses the dist as the index. + :param dist: + :param index: + :return: + ''' try: maxIndex = len(self.data.gcode) - 1 - targetIndex = self.data.gcodeIndex + dist + if index is True: + targetIndex = dist + else: + targetIndex = self.data.gcodeIndex + dist - # print "targetIndex="+str(targetIndex) # check to see if we are still within the length of the file if maxIndex < 0: # break if there is no data to read return @@ -317,159 +772,277 @@ def moveGcodeIndex(self, dist): self.data.gcodeIndex = maxIndex else: self.data.gcodeIndex = targetIndex - gCodeLine = self.data.gcode[self.data.gcodeIndex] - # print self.data.gcode - # print "gcodeIndex="+str(self.data.gcodeIndex)+", gCodeLine:"+gCodeLine - xTarget = 0 - yTarget = 0 try: - x = re.search("X(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) - if x: - xTarget = float(x.groups()[0]) - self.data.previousPosX = xTarget - else: - xTarget = self.data.previousPosX - - y = re.search("Y(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) - - if y: - yTarget = float(y.groups()[0]) - self.data.previousPosY = yTarget - else: - yTarget = self.data.previousPosY - # self.gcodecanvas.positionIndicator.setPos(xTarget,yTarget,self.data.units) - # print "xTarget:"+str(xTarget)+", yTarget:"+str(yTarget) - position = {"xval": xTarget, "yval": yTarget, "zval": self.data.zval} - self.data.ui_queue.put( - "Action: positionMessage:_" + json.dumps(position) - ) # the "_" facilitates the parse + # send gcode position update to UI client + retval = self.sendGCodePositionUpdate(recalculate=True) + return retval except Exception as e: - print(e) - print("Unable to update position for new gcode line") + self.data.console_queue.put(str(e)) + self.data.console_queue.put("Unable to update position for new gcode line") return False return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def move(self, direction, distToMove): + ''' + Issues commands to move the sled + :param direction: direction to move + :param distToMove: distance to move + :return: + ''' + # if enabled, for diagonal movements, the x and y move distance will be calculated such that the total distance + # moved equals what was specified. For example, if enabled and command is issued to move one foot to top right, + # then the x and y coordinates will be calculated as the 0.707 feet so that a total of 1 foot is moved. If + # disabled, then the sled will move 1 foot left and 1 foot up, for a total distance of 1.414 feet. + if self.data.config.getValue("WebControl Settings","diagonalMove") == 1: + diagMove = round(math.sqrt(distToMove*distToMove/2.0), 4) + else: + diagMove = distToMove try: + self.data.sledMoving = True + self.data.gcode_queue.put("G91 ") if direction == "upLeft": - self.data.gcode_queue.put( - "G91 G00 X" - + str(-1.0 * distToMove) - + " Y" - + str(distToMove) - + " G90 " - ) + self.data.gcode_queue.put("G00 X"+ str(-1.0 * diagMove)+ " Y"+ str(diagMove)+ " ") elif direction == "up": - self.data.gcode_queue.put("G91 G00 Y" + str(distToMove) + " G90 ") + self.data.gcode_queue.put("G00 Y" + str(distToMove) + " ") elif direction == "upRight": - self.data.gcode_queue.put( - "G91 G00 X" + str(distToMove) + " Y" + str(distToMove) + " G90 " - ) + self.data.gcode_queue.put("G00 X" + str(diagMove) + " Y" + str(diagMove) + " ") elif direction == "left": - self.data.gcode_queue.put( - "G91 G00 X" + str(-1.0 * distToMove) + " G90 " - ) + self.data.gcode_queue.put("G00 X" + str(-1.0 * distToMove) + " ") elif direction == "right": - self.data.gcode_queue.put("G91 G00 X" + str(distToMove) + " G90 ") + self.data.gcode_queue.put("G00 X" + str(distToMove) + " ") elif direction == "downLeft": - self.data.gcode_queue.put( - "G91 G00 X" - + str(-1.0 * distToMove) - + " Y" - + str(-1.0 * distToMove) - + " G90 " - ) + self.data.gcode_queue.put("G00 X" + str(-1.0 * diagMove) + " Y" + str(-1.0 * diagMove) + " ") elif direction == "down": - self.data.gcode_queue.put( - "G91 G00 Y" + str(-1.0 * distToMove) + " G90 " - ) + self.data.gcode_queue.put("G00 Y" + str(-1.0 * distToMove) + " ") elif direction == "downRight": - self.data.gcode_queue.put( - "G91 G00 X" - + str(distToMove) - + " Y" - + str(-1.0 * distToMove) - + " G90 " - ) + self.data.gcode_queue.put("G00 X" + str(diagMove) + " Y" + str(-1.0 * diagMove) + " ") + else: + return False + self.data.gcode_queue.put("G90 ") + # keep track of the distToMove value + self.data.config.setValue("Computed Settings", "distToMove", distToMove) + self.data.sledMoving = False return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) + self.data.sledMoving = False return False def moveZ(self, direction, distToMoveZ): + ''' + Moves the Z-Axis a distance and direction + :param direction: + :param distToMoveZ: + :return: + ''' + try: - # distToMoveZ = float(msg['data']['distToMoveZ']) + #keep track of distToMoveZ value self.data.config.setValue("Computed Settings", "distToMoveZ", distToMoveZ) + # It's possible the front page is set for one units and when you go to z-axis control, you might switch + # to a different unit. Webcontrol keeps these units separate, so we need to make sure the machine is in + # the correct units when the z-axis move is sent unitsZ = self.data.config.getValue("Computed Settings", "unitsZ") + previousUnits = self.data.config.getValue("Computed Settings", "units") + self.data.zMoving = True if unitsZ == "MM": self.data.gcode_queue.put("G21 ") else: self.data.gcode_queue.put("G20 ") if direction == "raise": - self.data.gcode_queue.put( - "G91 G00 Z" + str(float(distToMoveZ)) + " G90 " - ) + self.data.gcode_queue.put("G91 ") + self.data.gcode_queue.put("G00 Z" + str(float(distToMoveZ)) + " ") + self.data.gcode_queue.put("G90 ") elif direction == "lower": - self.data.gcode_queue.put( - "G91 G00 Z" + str(-1.0 * float(distToMoveZ)) + " G90 " - ) - units = self.data.config.getValue("Computed Settings", "units") - if units == "MM": - self.data.gcode_queue.put("G21 ") - else: - self.data.gcode_queue.put("G20 ") + self.data.gcode_queue.put("G91 ") + self.data.gcode_queue.put("G00 Z" + str(-1.0 * float(distToMoveZ)) + " " ) + self.data.gcode_queue.put("G90 ") + # now, since we might have changed the units of the machine, make sure they are set back to what it was + # originally. + #units = self.data.config.getValue("Computed Settings", "units") + if previousUnits != unitsZ: + if previousUnits == "MM": + self.data.gcode_queue.put("G21 ") + else: + self.data.gcode_queue.put("G20 ") + self.data.zMoving = False return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) + self.data.zMoving = False return False - def updateSetting(self, setting, value): + + def touchZ(self): + ''' + Sends a gcode line to set z axis depth using touch plate. I've not personally tested this. + :return: + ''' try: - if setting == "toInches": - self.data.units = "INCHES" - self.data.config.setValue("Computed Settings", "units", self.data.units) - scaleFactor = 1.0 - self.data.gcodeShift = [ - self.data.gcodeShift[0] / scaleFactor, - self.data.gcodeShift[1] / scaleFactor, - ] - self.data.tolerance = 0.020 - self.data.gcode_queue.put("G20 ") - self.data.config.setValue("Computed Settings", "distToMove", value) - elif setting == "toMM": - self.data.units = "MM" - self.data.config.setValue("Computed Settings", "units", self.data.units) - scaleFactor = 25.4 + plungeDepth = self.data.config.getValue("Advanced Settings", "maxTouchProbePlungeDistance") + revertToInches = False + self.data.zMoving = True + if self.data.units == "INCHES": + revertToInches = True + self.data.gcode_queue.put("G21") + self.data.gcode_queue.put("G90 G38.2 Z-" + plungeDepth + " F1 M02") + if revertToInches: + self.data.gcode_queue.put("G20") + # don't think this line is needed + # todo: remove if not needed. + self.data.measureRequest = self.defineZ0() + self.data.zMoving = False + return True + except Exception as e: + self.data.console_queue.put(str(e)) + self.data.zMoving = False + return False + + def updateSetting(self, setting, value, fromGcode = False): + ''' + update settings that come from frontpage or from the gcode file. + :param setting: + :param value: + :param fromGcode: + :return: + ''' + try: + self.data.console_queue.put("at update setting from gcode("+str(fromGcode)+"): "+setting+" with value: "+str(value)) + # if front page button has been pressed or serialPortThread is going to send gcode with a G21 or G20.. + if setting == "toInches" or setting == "toMM": + # this shouldn't be reached any more after I reordered the processActions function + # todo: remove this if if not needed. + if self.data.uploadFlag == 1 and fromGcode == False: + self.data.ui_queue1.put("Alert", "Alert", "Cannot change units while sending gcode.") + return True + scaleFactor = 0 + if fromGcode: + # if from a gcode line, then update the get the distToMove value from storage and figure out the + # scaleFactor + value = float(self.data.config.getValue("Computed Settings", "distToMove")) + if self.data.units == "INCHES": + if setting == "toMM": + value = value * 25.4 + scaleFactor = 25.4 + else: + scaleFactor = 1.0 + if self.data.units == "MM": + if setting == "toInches": + value = value / 25.4 + scaleFactor = 1.0 / 25.4 + else: + scaleFactor = 1.0 + + if setting == "toInches": + # was metric, now going to imperial + self.data.units = "INCHES" + self.data.config.setValue("Computed Settings", "units", self.data.units) + # if scaleFactor == 0, then it wasn't previously set by the if fromGcode. + if scaleFactor == 0: + scaleFactor = 1.0/25.4 + self.data.tolerance = 0.020 + self.data.config.setValue("Computed Settings", "tolerance", self.data.tolerance) + # only send G20 to the controller if not already sending G20 + if not fromGcode: + self.data.gcode_queue.put("G20 ") + else: + # was imperial, now going to metric + self.data.units = "MM" + self.data.config.setValue("Computed Settings", "units", self.data.units) + # if scaleFactor == 0, then it wasn't previously set by the if fromGcode. + if scaleFactor == 0: + scaleFactor = 25.4 + self.data.tolerance = 0.5 + self.data.config.setValue("Computed Settings", "tolerance", self.data.tolerance) + # only send G21 to the controller if not already sending G21 + if not fromGcode: + self.data.gcode_queue.put("G21 ") + # update the gcodeShift coordinates to match units self.data.gcodeShift = [ - self.data.gcodeShift[0] / scaleFactor, - self.data.gcodeShift[1] / scaleFactor, + self.data.gcodeShift[0] * scaleFactor, + self.data.gcodeShift[1] * scaleFactor, ] - self.data.tolerance = 0.5 - self.data.gcode_queue.put("G21") + # The UI client sending this has already converted the distToMove to the correct value for the units self.data.config.setValue("Computed Settings", "distToMove", value) + # get the current homeX and homeY coordinates + oldHomeX = float(self.data.config.getValue("Advanced Settings", "homeX")) + oldHomeY = float(self.data.config.getValue("Advanced Settings", "homeY")) + # convert homeX and homeY to the correct units and save + self.data.config.setValue("Advanced Settings", "homeX", oldHomeX * scaleFactor) + self.data.config.setValue("Advanced Settings", "homeY", oldHomeY * scaleFactor) + # notify all UI clients that units have been changed and distToMove has been changed + self.data.ui_queue1.put("Action", "unitsUpdate", "") + self.data.ui_queue1.put("Action", "distToMoveUpdate", "") + # update the home position.. + position = {"xval": oldHomeX * scaleFactor, "yval": oldHomeY * scaleFactor} + self.data.ui_queue1.put("Action", "homePositionMessage", position) + # update the gcode position + self.sendGCodePositionUpdate(recalculate=True) elif setting == "toInchesZ": - self.data.units = "INCHES" + # this shouldn't be reached any more after I reordered the processActions function + # todo: remove this if if not needed. + if self.data.uploadFlag == 1: + self.data.ui_queue1.put("Alert", "Alert", "Cannot change units while sending gcode.") + return True + + #self.data.units = "INCHES" ### commented this out and added the unitZ self.data.config.setValue( - "Computed Settings", "unitsZ", self.data.units + "Computed Settings", "unitsZ", "INCHES" ) self.data.config.setValue("Computed Settings", "distToMoveZ", value) + self.data.ui_queue1.put("Action", "unitsUpdateZ", "") + self.data.ui_queue1.put("Action", "distToMoveUpdateZ", "") + elif setting == "toMMZ": - self.data.units = "MM" + # this shouldn't be reached any more after I reordered the processActions function + # todo: remove this if if not needed. + if self.data.uploadFlag == 1: + self.data.ui_queue1.put("Alert", "Alert", "Cannot change units while sending gcode.") + return True + #self.data.units = "MM" ### commented this out self.data.config.setValue( - "Computed Settings", "unitsZ", self.data.units + "Computed Settings", "unitsZ", "MM" ) self.data.config.setValue("Computed Settings", "distToMoveZ", value) + self.data.ui_queue1.put("Action", "unitsUpdateZ", "") + self.data.ui_queue1.put("Action", "distToMoveUpdateZ", "") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False + def rotateSprocket(self, sprocket, time): + ''' + Turns sprocket at 100 speed for given amount of time using B11 command + This command is used in PID tuning to try to get sprockets in a position without using encoder. + :param sprocket: + :param time: + :return: + ''' + try: + if time > 0: + self.data.gcode_queue.put("B11 "+sprocket+" S100 T"+str(time)) + else: + self.data.gcode_queue.put("B11 "+sprocket+" S-100 T"+str(abs(time))) + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def setSprockets(self, sprocket, degrees): + ''' + Moves sprocket a specified number of degrees. + :param sprocket: + :param degrees: + :return: + ''' try: + # calculate the amoount of chain to be fed out/in based upon sprocket circumference and degree degValue = round( float(self.data.config.getValue("Advanced Settings", "gearTeeth")) * float(self.data.config.getValue("Advanced Settings", "chainPitch")) @@ -477,32 +1050,47 @@ def setSprockets(self, sprocket, degrees): * degrees, 4, ) + # Adjust distance based upon chainOverSprocket value self.data.gcode_queue.put("G91 ") if ( self.data.config.getValue("Advanced Settings", "chainOverSprocket") - == "Top" + == "Bottom" ): - self.data.gcode_queue.put("B09 " + sprocket + str(degValue) + " ") - else: - self.data.gcode_queue.put("B09 " + sprocket + "-" + str(degValue) + " ") + degValue *= -1.0 + if self.data.config.getValue("Advanced Settings", "chainOverSprocket") == "Bottom": + if self.data.config.getValue("Computed Settings", "chainOverSprocketComputed") != 2: + self.data.ui_queue1.put("Alert", "Alert", "mismatch between setting and computed setting. set for bottom feed, but computed !=2. report as issue on github please") + if self.data.config.getValue("Advanced Settings", "chainOverSprocket") == "Top": + if self.data.config.getValue("Computed Settings", "chainOverSprocketComputed") != 1: + self.data.ui_queue1.put("Alert", "Alert", "mismatch between setting and computed setting. set for top feed, but computed != 1. report as issue on github please") + # send command + self.data.gcode_queue.put("B09 " + sprocket + str(degValue) + " ") self.data.gcode_queue.put("G90 ") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False - def setVerticalAutomatic(self): - # set the call back for the measurement + def setSprocketAutomatic(self): + ''' + Sets the call back for the automatic sprocket alignment and requests the measurement. + ''' try: self.data.measureRequest = self.getLeftChainLength # request a measurement self.data.gcode_queue.put("B10 L") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False def getLeftChainLength(self, dist): + ''' + Part of setSprocketAutomatic. Is called after the measurement is received. Left chain measurement is logged + and then callback is set to get the right chain measurement. + :param dist: + :return: + ''' self.leftChainLength = dist # set the call back for the measurement self.data.measureRequest = self.getRightChainLength @@ -510,33 +1098,67 @@ def getLeftChainLength(self, dist): self.data.gcode_queue.put("B10 R") def getRightChainLength(self, dist): + ''' + Part of setSprocketAutomatic. Is called after the measurement is received. Right chain measurement is logged + and then moveToVertical is called. + :param dist: + :return: + ''' self.rightChainLength = dist self.moveToVertical() def moveToVertical(self): - chainPitch = float(self.data.config.get("Advanced Settings", "chainPitch")) - gearTeeth = float(self.data.config.get("Advanced Settings", "gearTeeth")) + ''' + Using distances logged from previous calls, calculates how much to move the sprockets so that one tooth is + vertical. + :return: + ''' + chainPitch = float(self.data.config.getValue("Advanced Settings", "chainPitch")) + gearTeeth = float(self.data.config.getValue("Advanced Settings", "gearTeeth")) distPerRotation = chainPitch * gearTeeth distL = -1 * (self.leftChainLength % distPerRotation) distR = -1 * (self.rightChainLength % distPerRotation) + # Issue required move commands.. self.data.gcode_queue.put("G91 ") self.data.gcode_queue.put("B09 L" + str(distL) + " ") self.data.gcode_queue.put("B09 R" + str(distR) + " ") self.data.gcode_queue.put("G90 ") def setSprocketsZero(self): - # mark that the sprockets are straight up + ''' + Notify controller that the chain length is zero. This is called by the user after the sprockets are set to + vertical. + :return: + ''' try: self.data.gcode_queue.put("B06 L0 R0 ") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) + return False + + def setSprocketsDefault(self): + ''' + Notify controller that the chain length is equal to the extendChainLength distance. This is called by the user + after setting both sprockets to vertical and reapplying the appropriate chain links to the top teeth. + https://forums.maslowcnc.com/t/how-to-manually-reset-chains-the-easy-way/ + :return: + ''' + try: + self.data.gcode_queue.put("B08 ") + return True + except Exception as e: + self.data.console_queue.put(str(e)) return False def updatePorts(self): - # refresh the list of available comports + ''' + Updates the list of ports found on the computer. + :return: + ''' + self.data.console_queue.put("at Update Ports") portsList = [] try: if sys.platform.startswith("linux") or sys.platform.startswith("cygwin"): @@ -555,21 +1177,40 @@ def updatePorts(self): if len(portsList) == 0: portsList.append("None") self.data.comPorts = portsList - self.data.ui_queue.put("Action: updatePorts") + # send updated list to UI client + self.data.ui_queue1.put("Action", "updatePorts", "") return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False + def acceptTriangularKinematicsResults(self): + ''' + Calls function to accept the results of the triangular calibration. + Todo: call directly from processActions. + :return: + ''' + try: + self.data.triangularCalibration.acceptTriangularKinematicsResults() + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def calibrate(self, result): + ''' + Sends form data for triangular calibration to the triangular calibration routine to calculate and then return + results to the UI client + :param result: + :return: + ''' try: motorYoffsetEst, rotationRadiusEst, chainSagCorrectionEst, cut34YoffsetEst = self.data.triangularCalibration.calculate( result ) - print(motorYoffsetEst) - print(rotationRadiusEst) - print(chainSagCorrectionEst) - if motorYoffsetEst == False: + if not motorYoffsetEst: + # if something didn't go correctly, motorYoffsetEst would have been returned as none return False return ( motorYoffsetEst, @@ -577,24 +1218,76 @@ def calibrate(self, result): chainSagCorrectionEst, cut34YoffsetEst, ) - """ - self.data.config.setValue('Maslow Settings', 'motorOffsetY', str(motorYoffsetEst)) - self.data.config.setValue('Advanced Settings', 'rotationRadius', str(rotationRadiusEst)) - self.data.config.setValue('Advanced Settings', 'chainSagCorrection', str(chainSagCorrectionEst)) + except Exception as e: + self.data.console_queue.put(str(e)) + return False - # With new calibration parameters return sled to workspace center + def holeyCalibrate(self, result): + ''' + Sends form data for holey calibration to the triangular calibration routine to calculate and then return + results to the UI client + :param result: + :return: + ''' + try: + motorYoffsetEst, distanceBetweenMotors, leftChainTolerance, rightChainTolerance, calibrationError = self.data.holeyCalibration.Calibrate( + result + ) + if not motorYoffsetEst: + # if something didn't go correctly, motorYoffsetEst would have been returned as none + return False + return ( + motorYoffsetEst, + distanceBetweenMotors, + leftChainTolerance, + rightChainTolerance, + calibrationError, + ) + except Exception as e: + self.data.console_queue.put(str(e)) + return False - self.data.gcode_queue.put("G21 ") - self.data.gcode_queue.put("G90 ") - self.data.gcode_queue.put("G40 ") - self.data.gcode_queue.put("G0 X0 Y0 ") - """ + + def sendGCode(self, gcode): + ''' + Sends gcode entered to controller. Comes from the Gcode->Send GCode function + :param gcode: + :return: + ''' + try: + self.data.sentCustomGCode = gcode + gcodeLines = gcode.splitlines() + for line in gcodeLines: + self.data.gcode_queue.put(line) return True except Exception as e: - print(e) + self.data.console_queue.put(str(e)) return False - + def macro(self, number): + ''' + Sends gcode associated with macro buttons + :param number: + :return: + ''' + ''' + Ignore this stuff in this comment block.. used for testing gpio + try: + if number == 1: + print("here") + btn_pin = Device.pin_factory.pin(2) + btn_pin.drive_low() + return True + if number == 2: + print("here2") + self.data.gpioActions.setGPIOAction(3, "Stop") + return True + + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + ''' try: if number == 1: macro = self.data.config.getValue("Maslow Settings", "macro1") @@ -602,6 +1295,873 @@ def macro(self, number): macro = self.data.config.getValue("Maslow Settings", "macro2") self.data.gcode_queue.put(macro) return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + ''' + def testImage(self): + # + #Calls function to send the test image from optical calibration + #Todo: move to processAction + #:return: + # + try: + self.data.opticalCalibration.testImage() + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + ''' + def adjustCenter(self, dist): + ''' + Used in optical calibration to allow user to raise/lower the center point and then move there. + :param dist: + :return: + ''' + try: + motorOffsetY = float(self.data.config.getValue("Maslow Settings","motorOffsetY"))+dist + self.data.config.setValue('Maslow Settings', 'motorOffsetY', str(motorOffsetY)) + if not self.returnToCenter(): + return False + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def processSettingRequest(self, section, setting): + ''' + Returns requested settings to the UI clients. Needed when a client connects or reconnects to get in sync + :param section: + :param setting: + :return: + ''' + try: + if setting == "homePosition": + # send home position + homeX = self.data.config.getValue("Advanced Settings", "homeX") + homeY = self.data.config.getValue("Advanced Settings", "homeY") + position = {"xval": homeX, "yval": homeY} + self.data.ui_queue1.put("Action", "homePositionMessage", position) + return None, None + elif setting == "calibrationCurve": + # send optical calibration curve values + try: + xCurve = [0,0,0,0,0,0] + yCurve = [0,0,0,0,0,0] + xCurve[0] = float(self.data.config.getValue('Optical Calibration Settings', 'calX0')) + xCurve[1] = float(self.data.config.getValue('Optical Calibration Settings', 'calX1')) + xCurve[2] = float(self.data.config.getValue('Optical Calibration Settings', 'calX2')) + xCurve[3] = float(self.data.config.getValue('Optical Calibration Settings', 'calX3')) + xCurve[4] = float(self.data.config.getValue('Optical Calibration Settings', 'calX4')) + xCurve[5] = float(self.data.config.getValue('Optical Calibration Settings', 'calX5')) + yCurve[0] = float(self.data.config.getValue('Optical Calibration Settings', 'calY0')) + yCurve[1] = float(self.data.config.getValue('Optical Calibration Settings', 'calY1')) + yCurve[2] = float(self.data.config.getValue('Optical Calibration Settings', 'calY2')) + yCurve[3] = float(self.data.config.getValue('Optical Calibration Settings', 'calY3')) + yCurve[4] = float(self.data.config.getValue('Optical Calibration Settings', 'calY4')) + yCurve[5] = float(self.data.config.getValue('Optical Calibration Settings', 'calY5')) + data = {"curveX": xCurve, "curveY": yCurve} + self.data.ui_queue1.put("Action", "updateOpticalCalibrationCurve", data) + except Exception as e: + self.data.console_queue.put(str(e)) + elif setting == "calibrationError": + # send calibration error matrix + try: + xyErrorArray = self.data.config.getValue("Optical Calibration Settings","xyErrorArray") + # parse the error array because its stored as a long string + errorX, errorY = self.data.config.parseErrorArray(xyErrorArray, True) + data = {"errorX": errorX, "errorY": errorY} + self.data.ui_queue1.put("Action", "updateOpticalCalibrationError", data) + except Exception as e: + self.data.console_queue.put(str(e)) + elif setting == "pauseButtonSetting": + # send current pause button state + try: + if self.data.uploadFlag == 0 or self.data.uploadFlag == 1: + return setting, "Pause" + else: + return setting, "Resume" + except Exception as e: + self.data.console_queue.put(str(e)) + else: + # send whatever is being request + if setting == "units": + # sled position messages from controller aren't sent unless there's a change, so we set the + # xval_prev to some silly number and when the next position message comes in from the controller, + # it will be processed and passed on to the UI clients. + self.data.xval_prev = -99999.0 + retval = self.data.config.getValue(section, setting) + # return the setting requested and its value. + return setting, retval + except Exception as e: + pass + return None, None + + def upgradeFirmware(self, version): + ''' + Upgrades the firmware in the controller + :param version: + :return: + ''' + try: + # if this is a pyinstaller release, find out where the root is... it could be a temp directory if single + # file + if self.data.platform == "PYINSTALLER": + home = os.path.join(self.data.platformHome) + else: + home = "." + if version == 0: + self.data.ui_queue1.put("SpinnerMessage", "", "Custom Firmware Update in Progress, Please Wait.") + path = home+"/firmware/madgrizzle/*.hex" + if version == 1: + self.data.ui_queue1.put("SpinnerMessage", "", "Stock Firmware Update in Progress, Please Wait.") + path = home+"/firmware/maslowcnc/*.hex" + if version == 2: + self.data.ui_queue1.put("SpinnerMessage", "", "Holey Firmware Update in Progress, Please Wait.") + path = home+"/firmware/holey/*.hex" + # wait half second.. not sure why.. + time.sleep(.5) + t0 = time.time()*1000 + portClosed = False + # request the the serial port is closed + self.data.serialPort.closeConnection() + # give it five seconds to close + while (time.time()*1000 - t0) < 5000: + if self.data.serialPort.getConnectionStatus(): + portClosed = True + break + # wait 1.5 seconds.. not sure why... + time.sleep(1.5) + # if port is closed, then upgrade firmware.. + if portClosed: + # works if there is only only valid hex file in the directory + for filename in glob.glob(path): + port = self.data.comport + # this was commented out below. probably not needed. Todo: cleanup + #if home != "": + # cmd = "\"C:\\Program Files (x86)\\Arduino\\hardware\\tools\\avr\\bin\\avrdude\" -Cavr/avrdude.conf -v -patmega2560 -cwiring -P" + port + " -b115200 -D -Uflash:w:" + filename + ":i" + #else: + cmd = home+"/tools/avrdude -C"+home+"/tools/avrdude.conf -v -patmega2560 -cwiring -P"+port+" -b115200 -D -Uflash:w:"+filename+":i" + #print(cmd) + # I think this is blocking.. + x = os.system(cmd) + self.data.connectionStatus = 0 + #print(x) + #print("closing modals") + # close off the modals and put away the spinner. + self.data.ui_queue1.put("Action", "closeModals", "Notification:") + return True + else: + self.data.ui_queue1.put("Action", "closeModals", "Notification:") + print("Port not closed") + return False + except Exception as e: + self.data.console_log.put(str(e)) + return False + + + def createDirectory(self, _directory): + ''' + Called to create a directory when saving gcode + :param _directory: + :return: + ''' + try: + home = self.data.config.getHome() + directory = home + "/.WebControl/gcode/" + _directory + if not os.path.isdir(directory): + os.mkdir(directory) + data = {"directory": _directory} + self.data.ui_queue1.put("Action", "updateDirectories", data) except Exception as e: print(e) + return True + + def sendGCodePositionUpdate(self, gCodeLineIndex=None, recalculate=False): + ''' + Send the updated gcode position. + :param gCodeLineIndex: Specific gcode index to send position based upon + :param recalculate: recalculate position by parsing through the gcode file. + :return: + ''' + if self.data.gcode: + if gCodeLineIndex is None: + gCodeLineIndex = self.data.gcodeIndex + gCodeLine = self.data.gcode[gCodeLineIndex] + + if not recalculate and gCodeLine.find("(") == -1 and gCodeLine.find(";") == -1: + # parse the position from the gcode line or use previous x, y, or z position if not present. Works only + # if in absolute mode + x = re.search("X(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + if x: + if self.data.positioningMode == 0: + xTarget = float(x.groups()[0]) + else: + xTarget = float(x.groups()[0]) + self.data.previousPosX + self.data.previousPosX = xTarget + else: + xTarget = self.data.previousPosX + + y = re.search("Y(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + + if y: + if self.data.positioningMode == 0: + yTarget = float(y.groups()[0]) + else: + yTarget = float(y.groups()[0]) + self.data.previousPosY + self.data.previousPosY = yTarget + else: + yTarget = self.data.previousPosY + + z = re.search("Z(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + + if z: + if self.data.positioningMode == 0: + zTarget = float(z.groups()[0]) + else: + zTarget = float(z.groups()[0]) + self.data.previousPosZ + self.data.previousPosZ = zTarget + else: + zTarget = self.data.previousPosZ + else: + # if directed to recalculate or there's a comment in the line, then use more time consuming method. + xTarget, yTarget, zTarget = self.findPositionAt(self.data.gcodeIndex) + + # correct for scaling. If the gcode line is in one units but machine is in different units, then need + # to make adjustment. This might occur if a gcode is loaded that's metric and then the user switches + # the front page to imperial and then changes the gcode index. + scaleFactor = 1.0 + if self.data.gcodeFileUnits == "MM" and self.data.units == "INCHES": + scaleFactor = 1/25.4 + if self.data.gcodeFileUnits == "INCHES" and self.data.units == "MM": + scaleFactor = 25.4 + + # send the position to the UI client + position = {"xval": xTarget * scaleFactor, "yval": yTarget * scaleFactor,"zval": zTarget * scaleFactor, "gcodeLine": gCodeLine, "gcodeLineIndex": gCodeLineIndex} + self.data.ui_queue1.put("Action", "gcodePositionMessage", position) + return True + + def moveTo(self, posX, posY): + ''' + Commands controller to move sled to specified coordinates from the contextmenu moveto command(always in inches) + :param posX: + :param posY: + :return: + ''' + # make sure not out of range. + bedHeight = float(self.data.config.getValue("Maslow Settings","bedHeight"))/25.4 + bedWidth = float(self.data.config.getValue("Maslow Settings", "bedWidth"))/25.4 + try: + if posX<=bedWidth/2 and posX>=bedWidth/-2 and posY<=bedHeight/2 and posY>=bedHeight/-2: + self.data.sledMoving = True + if self.data.units == "INCHES": + posX=round(posX,4) + posY=round(posY,4) + else: + # convert to mm + posX=round(posX*25.4,4) + posY=round(posY*25.4,4) + self.data.gcode_queue.put( + "G90 G00 X" + + str(posX) + + " Y" + + str(posY) + + " " + ) + self.data.sledMoving = False + return True + return False + except Exception as e: + self.data.console_queue.put(str(e)) + self.data.sledMoving = False + return False + + def processGCode(self): + ''' + This function processes the gcode up to the current gcode index to develop a set of + gcodes to send to the controller upon the user starting a run. This function is intended + to ensure that the sled is in the correct location and the controller is in the correct + state prior to starting the current gcode move. Currently processed are relative/absolute + positioning (G90/G91), imperial/metric units (G20/G21) and x, y and z positions + ''' + positioning = "G90 " + zAxisSafeHeight = float(self.data.config.getValue("Maslow Settings", "zAxisSafeHeight")) + zAxisFeedRate = 12.8 # currently hardcoded, but Todo: Add setting + xyAxisFeedRate = float(self.data.config.getValue("Advanced Settings", "maxFeedrate")) + positioning = "G90 " + units = "G20 " + homeX = float(self.data.config.getValue("Advanced Settings", "homeX")) + homeY = float(self.data.config.getValue("Advanced Settings", "homeY")) + previousUnits = self.data.config.getValue("Computed Settings", "units") + if previousUnits == "INCHES": + previousUnits = "G20 " + else: + previousUnits = "G21 " + xpos = homeX + ypos = homeY + zpos = 0 + tool = None + spindle = None + laser = None + dwell = None + # start parsing through gcode file up to the index + for x in range(self.data.gcodeIndex): + filtersparsed = re.sub(r'\(([^)]*)\)', '', self.data.gcode[x]) # replace mach3 style gcode comments with newline + filtersparsed = re.sub(r';([^\n]*)?', '\n', filtersparsed) # replace standard ; initiated gcode comments with nothing + if not filtersparsed.isspace(): # if all spaces, don't send. likely a comment. #self.data.gcode[x][0] != "(": + #lines = self.data.gcode[x].split(" ") + lines = filtersparsed.split(" ") + if lines: + finalLines = [] + # I think this splits everything up and reassembles them so that each line starts with a M, G or T + # I must of had a reason to do so + for line in lines: + if len(line) > 0: + if line[0] == "M" or line[0] == "G" or line[0] == "T" or len(finalLines) == 0: + finalLines.append(line) + else: + finalLines[-1] = finalLines[-1] + " " + line + # start processing the lines, keeping track of the state variables. + for line in finalLines: + if line[0]=='G': + if line.find("G90") != -1: + positioning = "G90 " + if line.find("G91") != -1: + positioning = "G91 " + if line.find("G20") != -1: + units = "G20 " + if previousUnits != units: #previous metrics now imperial + homeX = xpos / 25.4 + homeY = ypos / 25.4 + xpos = xpos / 25.4 + ypos = ypos / 25.4 + previousUnits = units + if line.find("G21") != -1: + units = "G21 " + if previousUnits != units: #previous imperial now metrics + homeX = xpos * 25.4 + homeY = ypos * 25.4 + xpos = xpos * 25.4 + ypos = ypos * 25.4 + previousUnits = units + if line.find("X") != -1: + _xpos = re.search("X(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", line) + if positioning == "G91 ": + xpos = xpos+float(_xpos.groups()[0]) + else: + xpos = float(_xpos.groups()[0])+homeX + if line.find("Y") != -1: + _ypos = re.search("Y(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", line) + if positioning == "G91 ": + ypos = ypos+float(_ypos.groups()[0]) + else: + ypos = float(_ypos.groups()[0])+homeY + if line.find("Z") != -1: + _zpos = re.search("Z(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", line) + if positioning == "G91 ": + zpos = zpos+float(_zpos.groups()[0]) + else: + zpos = float(_zpos.groups()[0]) + if line.find("G4") != -1: + dwell = line[3:] + if line.find("G04") != -1: + dwell = line[4:] + if line.find("F") != -1: + _feedRate = re.search("F(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", line) + _feedRateFloat = float(_feedRate.groups()[0]) + if line.find("X") != -1 or line.find("Y") == -1: + xyAxisFeedRate = _feedRateFloat + if line.find("Z") != -1: + zAxisFeedRate = _feedRateFloat + if line[0] == 'M': + if line.find("M3") != -1 or line.find("M03") != -1: + spindle = "M3 " + if line.find("M4") != -1 or line.find("M05") != -1: + spindle = "M4 " + if line.find("M5") != -1 or line.find("M05") != -1: + spindle = "M5 " + if line.find("M106") != -1: + laser = "M106 " + if line.find("M107") != -1: + laser = "M107 " + if line.find("M16") != -1: + laser = "M107 " + if line[0] == 'T': + tool = line[1:] #slice off the T + # now, after all that processing has been done, put machine in the correct state + # first, send the units command. + self.data.gcode_queue.put(units) + # if units is imperial, then change the zAxisSafeHeight + if units == "G20 ": + zAxisSafeHeight = zAxisSafeHeight / 25.4 + ''' + I had commented this out.. don't think it should be done since the units above will do it. + if units == "G20 ": + print("is G20") + self.data.actions.updateSetting("toInches", 0, True) # value = doesn't matter + + else: + print("is G21") + self.data.actions.updateSetting("toMM", 0, True) # value = doesn't matter + ''' + # move the Z-axis to the safe height + print("moving to safe height as part of processgcode") + #force into absolute mode + self.data.gcode_queue.put("G90 ") + self.data.gcode_queue.put("G0 Z"+str(round(zAxisSafeHeight, 4))+" F"+str(round(zAxisFeedRate, 4))) + # move the sled to the x, y coordinate it is supposed to be. + self.data.gcode_queue.put("G0 X"+str(round(xpos, 4))+" Y"+str(round(ypos, 4))+" F"+str(round(xyAxisFeedRate, 4))) + # if there is a tool, then send tool change command. + if tool is not None: + self.data.gcode_queue.put("T"+tool+" M6 ") + # if there is a spindle command, then send it. + if spindle is not None: + self.data.gcode_queue.put(spindle) + # if there is a laser command, then send it. + if laser is not None: + self.data.gcode_queue.put(laser) + # if there is a dwell command, then send it. + if dwell is not None: + self.data.gcode_queue.put("G4 "+dwell) + # move the z-axis to where it is supposed to be. + print("moving to where it should be as part of processgcode") + self.data.gcode_queue.put("G0 Z" + str(round(zpos, 4)) + " ") + # finally, put the machine in the appropriate positioning + # I have no idea if this really works for G91 gcode files.. + self.data.gcode_queue.put(positioning) + + def findPositionAt(self, index): + ''' + Find the x,y,z gcode position at a given index when simple calcs don't work. Parse through the file. + :param index: + :return: + ''' + xpos = 0 + ypos = 0 + zpos = 0 + positioning = "G90 " + for x in range(index): + filtersparsed = re.sub(r'\(([^)]*)\)', '', self.data.gcode[x]) # replace mach3 style gcode comments with newline + filtersparsed = re.sub(r';([^\n]*)?', '\n', filtersparsed) # replace standard ; initiated gcode comments with "" + if not filtersparsed.isspace(): # if all spaces, don't send. likely a comment. #self.data.gcode[x][0] != "(": + listOfLines = filter(None, re.split("(G)", filtersparsed)) # self.data.gcode[x])) # self.data.gcode[x].split("G") + # it is necessary to split the lines along G commands so that commands concatenated on one line + # are processed correctly + for line in listOfLines: + line = 'G'+line + if line[0] == 'G': + if line.find("G90") != -1: + positioning = "G90 " + if line.find("G91") != -1: + positioning = "G91 " + if line.find("X") != -1: + _xpos = re.search("X(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", line) + if positioning == "G91 ": + xpos = xpos + float(_xpos.groups()[0]) + else: + xpos = float(_xpos.groups()[0]) + if line.find("Y") != -1: + _ypos = re.search("Y(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", line) + if positioning == "G91 ": + ypos = ypos + float(_ypos.groups()[0]) + else: + ypos = float(_ypos.groups()[0]) + if line.find("Z") != -1: + _zpos = re.search("Z(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", line) + if positioning == "G91 ": + zpos = zpos + float(_zpos.groups()[0]) + else: + zpos = float(_zpos.groups()[0]) + #print("xpos="+str(xpos)+", ypos="+str(ypos)+", zpoz="+str(zpos)+" for index="+str(index)) + return xpos, ypos, zpos + + def adjustChain(self, chain): + ''' + Called during the chain extend routine + :param chain: + :return: + ''' + try: + for x in range(6): + self.data.ui_queue1.put("Action", "updateTimer", chain+":"+str(5-x)) + self.data.console_queue.put("Action:updateTimer_" + chain + ":" + str(5 - x)) + time.sleep(1) + if chain == "left": + self.data.gcode_queue.put("B02 L1 R0 ") + self.data.measureRequest = self.issueStopCommand + self.data.gcode_queue.put("B10 L") + if chain == "right": + self.data.gcode_queue.put("B02 L0 R1 ") + self.data.measureRequest = self.issueStopCommand + self.data.gcode_queue.put("B10 R") + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def issueStopCommand(self, distance): + try: + self.data.quick_queue.put("!") + with self.data.gcode_queue.mutex: + self.data.gcode_queue.queue.clear() + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def toggleCamera(self): + ''' + Turns camera on or off. If its suspended, it's read (though I can't explain why at this moment). + :return: + ''' + try: + status = self.data.camera.status() + if status == "stopped": + self.data.camera.start() + if status == "suspended": + self.data.camera.read() + if status == "running": + self.data.camera.stop() + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def cameraStatus(self): + ''' + Sends the status of the camera to the UI client. Not sure why its not called requestCameraStatus + Todo: update name to request cameraStatus + :return: + ''' + try: + status = self.data.camera.status() + if status == "stopped": + self.data.ui_queue1.put("Action", "updateCamera", "off") + if status == "suspended": + self.data.ui_queue1.put("Action", "updateCamera", "off") + if status == "running": + self.data.ui_queue1.put("Action", "updateCamera", "on") + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def queryCamera(self): + ''' + Query the camera's settings. Probably could be called directly by processAction + Todo: move to processAction + :return: + ''' + try: + self.data.camera.getSettings() + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def velocityPIDTest(self, parameters): + ''' + Send commands to start the veloctiy pid test + Todo: further explain this + :param parameters: + :return: + ''' + try: + print(parameters) + print(parameters["KpV"]) + self.data.config.setValue("Advanced Settings", "KpV", parameters["KpV"]) + self.data.config.setValue("Advanced Settings", "KiV", parameters["KiV"]) + self.data.config.setValue("Advanced Settings", "KdV", parameters["KdV"]) + gcodeString = "B13 "+parameters["vMotor"]+"1 S"+parameters["vStart"]+" F"+parameters["vStop"]+" I"+parameters["vSteps"]+" V"+parameters["vVersion"] + print(gcodeString) + self.data.PIDVelocityTestVersion = parameters["vVersion"] + self.data.gcode_queue.put(gcodeString) + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def positionPIDTest(self, parameters): + ''' + Send commands to start the position pid test + Todo: further explain this + :param parameters: + :return: + ''' + + try: + print(parameters) + print(parameters["KpP"]) + self.data.config.setValue("Advanced Settings", "KpPos", parameters["KpP"]) + self.data.config.setValue("Advanced Settings", "KiPos", parameters["KiP"]) + self.data.config.setValue("Advanced Settings", "KdPos", parameters["KdP"]) + + gcodeString = "B14 "+parameters["pMotor"]+"1 S"+parameters["pStart"]+" F"+parameters["pStop"]+" I"+parameters["pSteps"]+" T"+parameters["pTime"]+" V"+parameters["pVersion"] + print(gcodeString) + self.data.PIDPositionTestVersion = parameters["pVersion"] + self.data.gcode_queue.put(gcodeString) + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def velocityPIDTestRun(self, command, msg): + ''' + + :param command: + :param msg: + :return: + ''' + try: + if command == 'stop': + self.data.inPIDVelocityTest = False + print("PID velocity test stopped") + print(self.data.PIDVelocityTestData) + data = json.dumps({"result": "velocity", "version": self.data.PIDVelocityTestVersion, "data": self.data.PIDVelocityTestData}) + self.data.ui_queue1.put("Action", "updatePIDData", data) + self.stopRun() + if command == 'running': + if msg.find("Kp=") == -1: + if self.data.PIDVelocityTestVersion == "2": + if msg.find("setpoint") == -1: + self.data.PIDVelocityTestData.append(msg) + else: + self.data.PIDVelocityTestData.append(float(msg)) + if command == 'start': + self.data.inPIDVelocityTest = True + self.data.PIDVelocityTestData = [] + print("PID velocity test started") + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def positionPIDTestRun(self, command, msg): + try: + if command == 'stop': + self.data.inPIDPositionTest = False + print("PID position test stopped") + print(self.data.PIDPositionTestData) + data = json.dumps({"result": "position", "version": self.data.PIDPositionTestVersion, "data": self.data.PIDPositionTestData}) + self.data.ui_queue1.put("Action", "updatePIDData", data) + self.stopRun() + if command == 'running': + if msg.find("Kp=") == -1: + if self.data.PIDPositionTestVersion == "2": + if msg.find("setpoint") == -1: + self.data.PIDPositionTestData.append(msg) + else: + self.data.PIDPositionTestData.append(float(msg)) + if command == 'start': + self.data.inPIDPositionTest = True + self.data.PIDPositionTestData = [] + print("PID position test started") + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def updateGCode(self, gcode): + try: + #print(gcode) + homeX = float(self.data.config.getValue("Advanced Settings", "homeX")) + homeY = float(self.data.config.getValue("Advanced Settings", "homeY")) + + if self.data.units == "MM": + scaleFactor = 25.4 + else: + scaleFactor = 1.0 + self.data.gcodeShift = [ + homeX, + homeY + ] + + self.data.gcodeFile.loadUpdateFile(gcode) + self.data.ui_queue1.put("Action", "gcodeUpdate", "") + return True + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def downloadDiagnostics(self): + try: + timestr = time.strftime("%Y%m%d-%H%M%S") + filename = self.data.config.home+"/.WebControl/"+"wc_diagnostics_"+timestr+".zip" + zipObj = zipfile.ZipFile(filename, 'w') + path1 = self.data.config.home+"/.WebControl/webcontrol.json" + zipObj.write(path1, os.path.basename(path1)) + path1 = self.data.config.home + "/.WebControl/alog.txt" + zipObj.write(path1, os.path.basename(path1)) + path1 = self.data.config.home + "/.WebControl/log.txt" + zipObj.write(path1, os.path.basename(path1)) + zipObj.close() + return filename + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def clearLogs(self): + try: + retval = self.data.logger.deleteLogFiles() + return retval + except Exception as e: + self.data.console_queue.put(str(e)) + return False + ''' + def checkForLatestPyRelease(self): + if True: #self.data.platform=="PYINSTALLER": + print("check for pyrelease") + g = Github() + repo = g.get_repo("madgrizzle/WebControl") + releases = repo.get_releases() + latest = 0 + latestRelease = None + type = self.data.pyInstallType + platform = self.data.pyInstallPlatform + for release in releases: + try: + tag_name = re.sub(r'[v]',r'',release.tag_name) + print(release.body) + #print(tag_name) + if float(tag_name) > latest: + latest = float(tag_name) + latestRelease = release + + except: + print("error parsing tagname") + print(latest) + if latest>self.data.pyInstallCurrentVersion: + if latestRelease is not None: + print(latestRelease.tag_name) + assets = latestRelease.get_assets() + for asset in assets: + if asset.name.find(type) != -1 and asset.name.find(platform) != -1: + print(asset.name) + print(asset.url) + self.data.ui_queue1.put("Action", "pyinstallUpdate", "on") + self.data.pyInstallUpdateAvailable = True + self.data.pyInstallUpdateBrowserUrl = asset.browser_download_url + self.data.pyInstallUpdateVersion = latest + + def processAbsolutePath(self, path): + index = path.find("main.py") + self.data.pyInstallInstalledPath = path[0:index-1] + print(self.data.pyInstallInstalledPath) + + def updatePyInstaller(self): + home = self.data.config.getHome() + if self.data.pyInstallUpdateAvailable == True: + if not os.path.exists(home+"/.WebControl/downloads"): + print("creating downloads directory") + os.mkdir(home+"/.WebControl/downloads") + fileList=glob.glob(home+"/.WebControl/downloads/*.gz") + for filePath in fileList: + try: + os.remove(filePath) + except: + print("error cleaning download directory: ",filePath) + print("---") + if self.data.pyInstallPlatform == "win32" or self.data.pyInstallPlatform == "win64": + filename = wget.download(self.data.pyInstallUpdateBrowserUrl, out=home+"\\.WebControl\\downloads") + else: + filename = wget.download(self.data.pyInstallUpdateBrowserUrl, out=home+"/.WebControl/downloads") + print(filename) + + if self.data.platform == "PYINSTALLER": + lhome = os.path.join(self.data.platformHome) + else: + lhome = "." + if self.data.pyInstallPlatform == "win32" or self.data.pyInstallPlatform == "win64": + path = lhome+"/tools/upgrade_webcontrol_win.bat" + copyfile(path, home+"/.WebControl/downloads/upgrade_webcontrol_win.bat") + path = lhome+"/tools/7za.exe" + copyfile(path, home+"/.WebControl/downloads/7za.exe") + self.data.pyInstallInstalledPath = self.data.pyInstallInstalledPath.replace('/','\\') + program_name = home+"\\.WebControl\\downloads\\upgrade_webcontrol_win.bat" + + else: + path = lhome+"/tools/upgrade_webcontrol.sh" + copyfile(path, home+"/.WebControl/downloads/upgrade_webcontrol.sh") + program_name = home+"/.WebControl/downloads/upgrade_webcontrol.sh" + self.make_executable(home+"/.WebControl/downloads/upgrade_webcontrol.sh") + tool_path = home+"\\.WebControl\\downloads\\7za.exe" + arguments = [filename, self.data.pyInstallInstalledPath, tool_path] + command = [program_name] + command.extend(arguments) + print("popening") + print(command) + subprocess.Popen(command) + return True + return False + + def make_executable(self, path): + print("1") + mode = os.stat(path).st_mode + print("2") + mode |= (mode & 0o444) >> 2 # copy R bits to X + print("3") + os.chmod(path, mode) + print("4") + ''' + + def addDirToZip(self, zipHandle, path, basePath=""): + basePath = basePath.rstrip("\\/") + "" + basePath = basePath.rstrip("\\/") + for root, dirs, files in os.walk(path): + # add dir itself (needed for empty dirs + zipHandle.write(os.path.join(root, ".")) + # add files + for file in files: + filePath = os.path.join(root, file) + inZipPath = filePath.replace(basePath, "", 1).lstrip("\\/") + # print filePath + " , " + inZipPath + zipHandle.write(filePath, inZipPath) + + def zipfolder(self, filename, target_dir): + zipobj = zipfile.ZipFile(filename, 'w', zipfile.ZIP_DEFLATED) + rootlen = len(target_dir) + 1 + for base, dirs, files in os.walk(target_dir): + for file in files: + fn = os.path.join(base, file) + zipobj.write(fn, fn[rootlen:]) + zipobj.close() + + + def backupWebControl(self): + try: + timestr = time.strftime("%Y%m%d-%H%M%S") + home = self.data.config.getHome() + filename = home+"/wc_backup_"+timestr+".zip" + print(filename) + folder = self.data.config.home+'/.WebControl' + print(folder) + self.zipfolder(filename, folder) + #self.addDirToZip(zipObj, self.data.config.home+'/.Webcontrol') + #zipObj.close() + return filename + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + + def restoreWebControl(self, fileName): + try: + with zipfile.ZipFile(fileName, 'r') as zipObj: + # Extract all the contents of zip file in different directory + zipObj.extractall(self.data.config.home+'/.Webcontrol') + retval = self.data.config.reloadWebControlJSON() + if retval is True: + self.data.gcode_queue.put("$$") + return retval + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def setFakeServo(self, value): + try: + if value: + self.data.gcode_queue.put("B99 ON") + else: + self.data.gcode_queue.put("B99 OFF") + return True + except Exception as e: + self.data.console_queue.put(str(e)) return False diff --git a/Actions/gpioActions.py b/Actions/gpioActions.py new file mode 100644 index 00000000..bc434d0e --- /dev/null +++ b/Actions/gpioActions.py @@ -0,0 +1,96 @@ +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs +from gpiozero.pins.mock import MockFactory +from gpiozero import Device, Button, LED +class GPIOActions(MakesmithInitFuncs): + def __init__(self): + pass + + ''' + get gpio settings + ''' + Buttons = [] + LEDs = [] + actionList = ["", "WebMCP Running", "Shutdown", "Stop", "Pause", "Play", "Home", "Return to Center","Pendant", "PlayLED", "PauseLED", "StopLED"] + + def getActionList(self): + return self.actionList + + def setup(self): + #self.setGPIOAction(2,"Stop") + setValues = self.data.config.getJSONSettingSection("GPIO Settings") + self.data.GPIOButtonService = self.data.config.getValue("Maslow Settings","MaslowButtonService") + if (self.data.GPIOButtonService): + self.data.wiiPendantPresent = self.data.config.getValue("Maslow Settings","wiiPendantPresent") + self.clidisplay = self.data.config.getValue("Maslow Settings", "clidisplay") + #print(setValues) + for setting in setValues: + if setting["value"] != "": + pinNumber = int(setting["key"][4:]) + if (self.data.GPIOButtonService == False): + self.setGPIOAction(pinNumber, setting["value"]) + + def setGPIOAction(self,pin, action): + # first remove pin assignments if already made + foundButton = None + for button in self.Buttons: + if button.pin.number == pin: + button.pin.close() + foundButton = button + break + if foundButton is not None: + self.Buttons.remove(foundButton) + + foundLED = None + for led in self.LEDs: + if led[1].pin.number == pin: + led[1].pin.close() + foundLED = led + break + if foundLED is not None: + self.LEDs.remove(foundLED) + + type, pinAction = self.getAction(action) + if type == "button": + button = Button(pin) + button.when_pressed = pinAction + self.Buttons.append(button) + print("set Button ", pin, " with action: ", action) + if type == "led": + _led = LED(pin) + led = (action,_led) + self.LEDs.append(led) + print("set LED with action: " + action) + #pause() + def getAction(self, action): + if action == "Stop": + return "button", self.data.actions.stopRun + elif action == "Pause": + return "button", self.data.actions.pauseRun + elif action == "Play": + return "button", self.data.actions.startRun + else: + return "led", None + + def runrun(self): + print("gpio button press detected") + self.data.actions.startRun() + + def causeAction(self, action, onoff): + for led in self.LEDs: + if led[0] == action: + print(led[1]) + if onoff == "on": + led[1].on() + else: + led[1].off() + print(led[1]) + if action == "PlayLED" and onoff == "on": + self.causeAction("PauseLED", "off") + self.causeAction("StopLED", "off") + if action == "PauseLED" and onoff == "on": + self.causeAction("PlayLED", "off") + self.causeAction("StopLED", "off") + if action == "StopLED" and onoff == "on": + self.causeAction("PauseLED", "off") + self.causeAction("PlayLED", "off") + diff --git a/Actions/holeyCalibration.py b/Actions/holeyCalibration.py new file mode 100644 index 00000000..9a2efd8c --- /dev/null +++ b/Actions/holeyCalibration.py @@ -0,0 +1,351 @@ +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs +import Actions.HoleySimulationKinematics as kinematics +import math +from scipy.optimize import least_squares +import numpy + +import itertools +import time +import re +import sys +import math +import base64 +import time +import os +import datetime + + +class HoleyCalibration(MakesmithInitFuncs): + + def __init__(self): + # can't do much because data hasn't been initialized yet + pass + + SP_D = 3629.025 + SP_motorOffsetY = 503.4 + SP_rotationDiskRadius = 138.1 + SP_leftChainTolerance = 0 + SP_rightChainTolerance = 0 + SP_sledWeight = 109.47 # N + SP_chainOverSprocket = False + + Opt_D = 3601.2 + Opt_motorOffsetY = 468.4 + Opt_rotationDiskRadius = 139.1 + Opt_leftChainTolerance = 0 + Opt_rightChainTolerance = 0 + Opt_sledWeight = 97.9 # N + + # Chain lengths @ each hole + ChainLengths = [] + MeasurementMap = [ + (1, 2), + (2, 3), + (4, 5), + (5, 6), + (1, 4), + (2, 5), + (3, 6), + (2, 4), + (1, 5), + (3, 5), + (2, 6)] + CutOrder = [1, 0, 3, 4, 5, 2] # Counter Clockwise, starting at top + IdealLengthArray = 0 + MeasuredLengthArray = 0 + DesiredLengthDeltaArray = 0 + + OptimizationOutput = 0 + + kin = kinematics.Kinematics() + kin.isQuadKinematics = False + + # Define function with input of (ideal lengths and) machine parameters (delta) and output of length error + def LengthDeltaFromIdeal(self, + DeltaArray): # Del_D,Del_motorOffsetY,Del_rotationDiskRadius,Del_chainSagCorrection): + self.kin.D = self.SP_D + DeltaArray[0] + self.kin.motorOffsetY = self.SP_motorOffsetY + DeltaArray[1] + self.kin.leftChainTolerance = self.SP_leftChainTolerance + DeltaArray[2] + self.kin.rightChainTolerance = self.SP_rightChainTolerance + DeltaArray[3] + self.kin.recomputeGeometry() + CalculatedPositions = [] + for LeftChainLength, RightChainLength in self.ChainLengths: + CalculatedPositions.append(self.kin.forward(LeftChainLength, RightChainLength)) + + return self.MeasuredLengthArray - self.CalculateMeasurements(CalculatedPositions) + + def InitialMeasurementError(self, Meas, idx): # For validating in GUI + Ideal = self.IdealLengthArray[idx] + return Ideal - Meas + + def ValidateMeasurement(self, Meas, idx): + if idx < 11: + Ideal = self.IdealLengthArray[idx] + return 0.1 > abs((Ideal - Meas) / Ideal) + else: + return Meas > 0.0 + + def CutTestPattern(self): + oldUnits = self.data.units + self.data.console_queue.put('Cutting Holey Calibration Test Pattern') + self.InitializeIdealXyCoordinates() + self.data.gcode_queue.put("G21") + self.data.gcode_queue.put("G90") # Switch to absolute mode + self.data.gcode_queue.put("G40") + self.data.gcode_queue.put("G17") + self.data.gcode_queue.put("M3") + for idx in self.CutOrder: + x, y = self.IdealCoordinates[idx] + self.data.console_queue.put('cutting index: ' + str(idx + 1)) + self.data.gcode_queue.put("G0 X" + str(x) + " Y" + str(y)) + self.data.gcode_queue.put("G0 Z-5") + self.data.gcode_queue.put("G0 Z5") + + self.data.gcode_queue.put("G0 X0 Y0") + self.data.gcode_queue.put("M5") + if oldUnits == "INCHES": + self.data.gcode_queue.put("G20") + return True + + def CalculateMeasurements(self, HolePositions): + # aH1x,aH1y,aH2x,aH2y,aH3x,aH3y,aH4x,aH4y,aH5x,aH5y,aH6x,aH6y + Measurements = [] + for StartHoleIdx, EndHoleIdx in self.MeasurementMap: + x1, y1 = HolePositions[StartHoleIdx - 1] + x2, y2 = HolePositions[EndHoleIdx - 1] + Measurements.append(self.GeometricLength(x1, y1, x2, y2)) + ToTopHole = 1 + Measurements.append( + self.GeometricLength(HolePositions[ToTopHole][0], HolePositions[ToTopHole][1], HolePositions[ToTopHole][0], + self.kin.machineHeight / 2)) + + return numpy.array(Measurements) + + def InitializeIdealXyCoordinates(self): + self.SP_D = float(self.data.config.getValue("Maslow Settings", "motorSpacingX")) + self.SP_motorOffsetY = float(self.data.config.getValue("Maslow Settings", "motorOffsetY")) + self.SP_rotationDiskRadius = float(self.data.config.getValue("Advanced Settings", "rotationRadius")) + self.SP_leftChainTolerance = float(self.data.config.getValue("Advanced Settings", "leftChainTolerance")) + self.SP_rightChainTolerance = float(self.data.config.getValue("Advanced Settings", "rightChainTolerance")) + self.SP_sledWeight = float(self.data.config.getValue("Maslow Settings", "sledWeight")) + if self.data.config.getValue("Advanced Settings", "chainOverSprocket") == "Top": + self.SP_chainOverSprocket = 1 + else: + self.SP_chainOverSprocket = 2 + self.kin.machineHeight = float(self.data.config.getValue("Maslow Settings","bedHeight")) + self.kin.machineWidth = float(self.data.config.getValue("Maslow Settings","bedWidth")) + workspaceHeight = self.kin.machineHeight + workspaceWidth = self.kin.machineWidth + aH1x = -(workspaceWidth / 2.0 - 254.0) + aH1y = (workspaceHeight / 2.0 - 254.0) + aH2x = 0 + IdealCoordinates = [ + (aH1x, aH1y), + (aH2x, aH1y), + (-aH1x, aH1y), + (aH1x, -aH1y), + (aH2x, -aH1y), + (-aH1x, -aH1y)] + self.IdealCoordinates = IdealCoordinates + self.kin.D = self.SP_D + self.kin.motorOffsetY = self.SP_motorOffsetY + self.kin.rotationDiskRadius = self.SP_rotationDiskRadius + self.kin.sledWeight = self.SP_sledWeight + self.kin.leftChainTolerance = self.SP_leftChainTolerance + self.kin.rightChainTolerance = self.SP_rightChainTolerance + self.kin.chainOverSprocket = self.SP_chainOverSprocket + self.kin.recomputeGeometry() + self.IdealLengthArray = self.CalculateMeasurements(IdealCoordinates) + + self.ChainLengths = [] + for x, y in IdealCoordinates: + self.ChainLengths.append(self.kin.inverse(x, y)) + return self.IdealLengthArray + + def SetMeasurements(self, Measurements): + self.MeasuredLengthArray = numpy.array(Measurements) + + def Calibrate(self, result): + self.InitializeIdealXyCoordinates() + measurements = self.processMeasurements(result) + self.SetMeasurements(measurements) + self.OptimizationOutput = least_squares(self.LengthDeltaFromIdeal, numpy.array([0, 0, 0, 0]), jac='2-point', + diff_step=.1, ftol=1e-11) + Deltas = self.OptimizationOutput.x + self.Opt_D = round(Deltas[0] + self.SP_D,5) + self.Opt_motorOffsetY = round(Deltas[1] + self.SP_motorOffsetY,5) + self.Opt_leftChainTolerance = round(Deltas[2] + self.SP_leftChainTolerance,5) + self.Opt_rightChainTolerance = round(Deltas[3] + self.SP_rightChainTolerance,5) + self.kin.D = self.Opt_D + self.kin.motorOffsetY = self.Opt_motorOffsetY + self.kin.leftChainTolerance = self.Opt_leftChainTolerance + self.kin.rightChainTolerance = self.Opt_rightChainTolerance + self.kin.recomputeGeometry() + totalError = self.ReportCalibration() + return self.Opt_motorOffsetY, self.Opt_D, self.Opt_leftChainTolerance, self.Opt_rightChainTolerance, totalError + + + def ReportCalibration(self): + self.data.console_queue.put('Optimized Errors') + totalError = 0 + for idx, pts, ms, cal, er in zip( + range(self.MeasuredLengthArray.size), + self.MeasurementMap, + self.MeasuredLengthArray, + self.CalibratedLengths(), + self.CalibratedLengthError()): + self.data.console_queue.put(('\tIndex : {}' + + '\n\t\tPoints Span : {} to {}' + + '\n\t\tMeasured Distance : {}' + + '\n\t\tCalibrated Distance: {}' + + '\n\t\tDistance Error : {}').format( + idx, pts[0], pts[1], ms, cal, er)) + totalError = totalError + er*er + + totalError = math.sqrt(totalError) + self.data.console_queue.put("") + self.data.console_queue.put("Distance Between Motors:") + self.data.console_queue.put(self.Opt_D) + self.data.console_queue.put("") + self.data.console_queue.put("Motor Y Offset:") + self.data.console_queue.put(self.Opt_motorOffsetY) + self.data.console_queue.put("") + self.data.console_queue.put("Left Chain Tolerance:") + self.data.console_queue.put(self.Opt_leftChainTolerance) + self.data.console_queue.put("") + self.data.console_queue.put("Right Chain Tolerance:") + self.data.console_queue.put(self.Opt_rightChainTolerance) + return totalError + + def CalibratedLengths(self): + return self.MeasuredLengthArray - self.OptimizationOutput.fun + + def CalibratedLengthError(self): + return self.OptimizationOutput.fun + + def HolePositionsFromChainLengths(self): + HolePositions = [] + for LeftChainLength, RightChainLength in self.ChainLengths: + HolePositions.append(self.kin.forward(LeftChainLength, RightChainLength)) + return HolePositions + + def SimulateMeasurement(self, D, motorOffsetY, leftChainTolerance, rightChainTolerance): + # Simulate Measurement. Modify machine parameters, use kin.forward to determine x,y coordinates. Return machine parameters to original + self.kin.D = D + self.kin.motorOffsetY = motorOffsetY + self.kin.leftChainTolerance = leftChainTolerance + self.kin.rightChainTolerance = rightChainTolerance + self.kin.recomputeGeometry() + + HolePositions = self.HolePositionsFromChainLengths() + + self.kin.D = self.SP_D + self.kin.motorOffsetY = self.SP_motorOffsetY + self.kin.rotationDiskRadius = self.SP_rotationDiskRadius + self.kin.sledWeight = self.SP_sledWeight + self.kin.leftChainTolerance = self.SP_leftChainTolerance + self.kin.rightChainTolerance = self.SP_rightChainTolerance + self.kin.recomputeGeometry() + + Measurements = self.CalculateMeasurements(HolePositions) + + self.SetMeasurements(Measurements) + + def processMeasurements(self, result): + measurements = [] + try: + M1 = float(result["M1"]) + self.data.console_queue.put(M1) + measurements.append(M1) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M1." ) + return False + try: + M2 = float(result["M2"]) + self.data.console_queue.put(M2) + measurements.append(M2) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M2." ) + return False + try: + M3 = float(result["M3"]) + self.data.console_queue.put(M3) + measurements.append(M3) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M3." ) + return False + try: + M4 = float(result["M4"]) + self.data.console_queue.put(M4) + measurements.append(M4) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M4." ) + return False + try: + M5 = float(result["M5"]) + self.data.console_queue.put(M5) + measurements.append(M5) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M5." ) + return False + try: + M6 = float(result["M6"]) + self.data.console_queue.put(M6) + measurements.append(M6) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M6." ) + return False + try: + M7 = float(result["M7"]) + self.data.console_queue.put(M7) + measurements.append(M7) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M7." ) + return False + try: + M8 = float(result["M8"]) + self.data.console_queue.put(M8) + measurements.append(M8) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M8.") + return False + try: + M9 = float(result["M9"]) + self.data.console_queue.put(M9) + measurements.append(M9) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M9." ) + return False + try: + M10 = float(result["M10"]) + self.data.console_queue.put(M10) + measurements.append(M10) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M10." ) + return False + try: + M11 = float(result["M11"]) + self.data.console_queue.put(M11) + measurements.append(M11) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M11." ) + return False + try: + M12 = float(result["M12"]) + self.data.console_queue.put(M12) + measurements.append(M12) + except: + self.data.message_queue.put("Message: Please enter a number for the distance M12." ) + return False + return measurements + + def GeometricLength(self,x1,y1,x2,y2): + return math.sqrt(math.pow(x1-x2,2) + math.pow(y1-y2,2)) + + def acceptCalibrationResults(self): + self.data.config.setValue('Maslow Settings', 'motorOffsetY', str(self.Opt_motorOffsetY)) + self.data.config.setValue('Maslow Settings', 'motorSpacingX', str(self.Opt_D)) + self.data.config.setValue('Advanced Settings', 'leftChainTolerance', str(self.Opt_leftChainTolerance)) + self.data.config.setValue('Advanced Settings', 'rightChainTolerance', str(self.Opt_rightChainTolerance)) + return True + diff --git a/Actions/opticalCalibration.py b/Actions/opticalCalibration.py deleted file mode 100644 index fa499957..00000000 --- a/Actions/opticalCalibration.py +++ /dev/null @@ -1,348 +0,0 @@ -from DataStructures.makesmithInitFuncs import MakesmithInitFuncs -from scipy.spatial import distance as dist -from imutils import perspective, contours - -# from imutils.video import VideoStream -# from Background.webcamVideoStream import WebcamVideoStream -# from imutils.video import WebcamVideoStream -import numpy as np -import imutils -import cv2 -import time -import re -import sys -import math -import base64 - - -class OpticalCalibration(MakesmithInitFuncs): - - camera = None - time.sleep(2.0) - gaussianBlurValue = 5 - cannyLowValue = 50 - cannyHighValue = 100 - opticalCenter = (None, None) - HomingPosX = 0 - HomingPosY = 0 - HomingX = 0 - HomingY = 0 - matrixSize = (31, 15) - calErrorsX = np.zeros(matrixSize) - calErrorsY = np.zeros(matrixSize) - inAutoMode = False - inMeasureOnlyMode = False - autoScanDirection = 0 - - def stopCut(self): - self.data.quick_queue.put("!") - with self.data.gcode_queue.mutex: - self.data.gcode_queue.queue.clear() - self.inAutoMode = False - self.inMeasureOnlyMode = False - - def midpoint(self, ptA, ptB): - return ((ptA[0] + ptB[0]) * 0.5, (ptA[1] + ptB[1]) * 0.5) - - def removeOutliersAndAverage(self, data): - mean = np.mean(data) - sd = np.std(data) - tArray = [ - x for x in data if ((x >= mean - 2.0 * sd) and (x <= mean + 2.0 * sd)) - ] - return np.average(tArray), np.std(tArray) - - def simplifyContour(self, c, sides=4): - tolerance = 0.01 - while True: - _c = cv2.approxPolyDP(c, tolerance * cv2.arcLength(c, True), True) - if len(_c) <= sides or tolerance > 0.5: - break - tolerance += 0.01 - if ( - len(_c) < sides - ): # went too small.. now lower the tolerance until four points or more are reached - while True: - tolerance -= 0.01 - _c = cv2.approxPolyDP(c, tolerance * cv2.arcLength(c, True), True) - if len(_c) >= sides or tolerance <= 0.1: - break - return _c - - def setCalibrationSettings(self, args): - self.markerX = float(args["markerX"]) * 25.4 - self.markerY = float(args["markerY"]) * 25.4 - self.centerX = float(args["centerX"]) - self.centerY = float(args["centerY"]) - self.scaleX = float(args["scaleX"]) - self.scaleY = float(args["scaleY"]) - self.tlX = int(args["tlX"]) - self.tlY = int(args["tlY"]) - self.brX = int(args["brX"]) - self.brY = int(args["brY"]) - - def translatePoint(self, xB, yB, xA, yA, angle): - cosa = math.cos((angle) * 3.141592 / 180.0) - sina = math.sin((angle) * 3.141592 / 180.0) - xB -= xA - yB -= yA - _xB = xB * cosa - yB * sina - _yB = xB * sina + yB * cosa - xB = _xB + xA - yB = _yB + yA - return xB, yB - - def HomeIn(self): - _posX = round(self.HomingPosX * 3.0 + self.HomingX / 25.4, 4) - _posY = round(self.HomingPosY * 3.0 + self.HomingY / 25.4, 4) - # self.updateTargetIndicator(_posX,_posY,"INCHES") - print( - "Moving to ({},{}) by trying [{}, {}]".format( - self.HomingPosX * 3.0, self.HomingPosY * 3.0, _posX, _posY - ) - ) - self.data.units = "INCHES" - self.data.gcode_queue.put("G20 ") - self.data.gcode_queue.put("G90 ") - self.data.gcode_queue.put("G0 X" + str(_posX) + " Y" + str(_posY) + " ") - self.data.gcode_queue.put("G91 ") - self.data.measureRequest = self.on_CenterOnSquare - # request a measurement - self.data.gcode_queue.put("B10 L") - - def on_CenterOnSquare(self, _dist, findCenter=False): - - dxList = np.zeros(shape=(10)) - dyList = np.zeros(shape=(10)) - diList = np.zeros(shape=(10)) - xBList = np.zeros(shape=(10)) - yBList = np.zeros(shape=(10)) - x = 0 - falseCounter = 0 - - while True: - (grabbed, image) = self.camera.read() - gray = cv2.cvtColor(image, cv2.COLOR_BGR2GRAY) - gray = cv2.GaussianBlur( - gray, (self.gaussianBlurValue, self.gaussianBlurValue), 0 - ) - edged = cv2.Canny(gray, self.cannyLowValue, self.cannyHighValue) - edged = cv2.dilate(edged, None, iterations=1) - edged = cv2.erode(edged, None, iterations=1) - cnts = cv2.findContours( - edged.copy(), cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE - ) - cnts = cnts[0] if imutils.is_cv2() else cnts[1] - (cnts, _) = contours.sort_contours(cnts) - colors = ( - (0, 0, 255), - (240, 0, 159), - (0, 165, 255), - (255, 255, 0), - (255, 0, 255), - ) - refObj = None - height, width, channels = image.shape - if self.opticalCenter[0] is None or self.opticalCenter[1] is None: - xA = int(width / 2) - yA = int(height / 2) - else: - xA, yA = self.opticalCenter - - maxArea = 0 - for cTest in cnts: - if cv2.contourArea(cTest) > maxArea: - maxArea = cv2.contourArea(cTest) - c = cTest - if cv2.contourArea(c) > 1000: - orig = image.copy() - # approximate to a square (i.e., four contour segments) - cv2.drawContours(orig, [c.astype("int")], -1, (255, 255, 0), 2) - # simplify the contour to get it as square as possible (i.e., remove the noise from the edges) - if findCenter: - sides = 20 - else: - sides = 4 - c = self.simplifyContour(c, sides) - cv2.drawContours(orig, [c.astype("int")], -1, (255, 0, 0), 2) - box = cv2.minAreaRect(c) - angle = box[-1] - if abs(angle + 90) < 30: - _angle = angle + 90 - else: - _angle = angle - box = cv2.cv.BoxPoints(box) if imutils.is_cv2() else cv2.boxPoints(box) - box = np.array(box, dtype="int") - box = perspective.order_points(box) - cv2.drawContours(orig, [box.astype("int")], -1, (0, 255, 0), 2) - # cv2.imwrite('testing/image-out'+str(x)+".png",orig) - if findCenter == False: - M = cv2.getRotationMatrix2D((xA, yA), _angle, 1) - orig = cv2.warpAffine(orig, M, (width, height)) - xB = np.average(box[:, 0]) - yB = np.average(box[:, 1]) - (tl, tr, br, bl) = box - (tlblX, tlblY) = self.midpoint(tl, bl) - (trbrX, trbrY) = self.midpoint(tr, br) - (tltrX, tltrY) = self.midpoint(tl, tr) - (blbrX, blbrY) = self.midpoint(bl, br) - xD = dist.euclidean((tlblX, tlblY), (trbrX, trbrY)) / self.markerX - yD = dist.euclidean((tltrX, tltrY), (blbrX, blbrY)) / self.markerY - if xD == 0: # doing this to catch bad calibrations and stop crashing - xD = 1.0 - if yD == 0: - yD = 1.0 - cos = math.cos(angle * 3.141592 / 180.0) - sin = math.sin(angle * 3.141592 / 180.0) - if _angle < 30: - _angle = _angle * -1.0 - if findCenter == False: - xB, yB = self.translatePoint(xB, yB, xA, yA, _angle) - Dx = dist.euclidean((xA, 0), (xB, 0)) / xD - if xA > xB: - Dx *= -1 - Dy = dist.euclidean((0, yA), (0, yB)) / yD - if yA < yB: - Dy *= -1 - Dist = math.sqrt(Dx ** 2.0 + Dy ** 2.0) - dxList[x] = Dx - dyList[x] = Dy - diList[x] = Dist - xBList[x] = xB - yBList[x] = yB - x += 1 - print("Processed Image " + str(x)) - if x == 10: - break - else: - falseCounter += 1 - if falseCounter == 10: - break - print("Got 10 images processed, " + str(falseCounter) + " images were bad") - if dxList.ndim != 0: - avgDx, stdDx = self.removeOutliersAndAverage(dxList) - avgDy, stdDy = self.removeOutliersAndAverage(dyList) - avgDi, stdDi = self.removeOutliersAndAverage(diList) - avgxB, stdxB = self.removeOutliersAndAverage(xBList) - avgyB, stdyB = self.removeOutliersAndAverage(yBList) - print("avgDx, stdDx:" + str(avgDx) + ", " + str(stdDx)) - print("avgDy, stdDy:" + str(avgDy) + ", " + str(stdDy)) - print("avgDy, stdDy:" + str(avgDy) + ", " + str(stdDy)) - print("avgxB, stdxB:" + str(avgxB) + ", " + str(stdxB)) - print("avgyB, stdyB:" + str(avgyB) + ", " + str(stdyB)) - imgencode = cv2.imencode(".png", orig)[1] - stringData = base64.b64encode(imgencode).decode() - self.data.opticalCalibrationImage = stringData - self.data.opticalCalibrationImageUpdated = True - self.HomingX += avgDx - self.HomingY += avgDy - if ((abs(avgDx) >= 0.125) or (abs(avgDy) >= 0.125)) and ( - findCenter == False - ): - print("Adjusting Location") - self.HomeIn() - else: - xS = self.HomingX + self.HomingPosX * 3 * 25.4 * (1.0 - self.scaleX) - yS = self.HomingY + self.HomingPosY * 3 * 25.4 * (1.0 - self.scaleY) - if self.inMeasureOnlyMode: - self.measuredErrorsX[self.HomingPosX + 15][7 - self.HomingPosY] = xS - self.measuredErrorsY[self.HomingPosX + 15][7 - self.HomingPosY] = yS - elif findCenter == False: - self.calErrorsX[self.HomingPosX + 15][7 - self.HomingPosY] = xS - self.calErrorsY[self.HomingPosX + 15][7 - self.HomingPosY] = yS - # else: - # self.ids.centerX.text = "%.1f" % avgxB - # self.ids.centerY.text = "%.1f" % avgyB - # self.opticalCenter = (avgxB, avgyB) - # self.updateScreenValues(self.HomingPosX, self.HomingPosY) - if self.inAutoMode: - self.on_AutoHome() - else: - print("avgDx,Dy:" + str(avgDx) + ", " + str(avgDy)) - print("Releasing Camera") - self.camera.release() - print("Done") - return False - - def on_AutoHome(self, measureMode=False): - - minX = self.tlX - maxX = self.brX - minY = self.tlY - maxY = self.brY - if measureMode == True: - print("Measure Only") - self.inMeasureOnlyMode = True - if self.inAutoMode == False: - self.HomingX = 0.0 - self.HomingY = 0.0 - self.HomingPosX = minX - self.HomingPosY = minY - self.HomingScanDirection = 1 - self.inAutoMode = True - self.HomeIn() - else: - # note, the self.HomingX and self.HomingY are not reinitialzed here - # The rationale is that the offset for the previous registration point is - # probably a good starting point for this registration point.. - if self.autoScanDirection == 0: # horizontal - print("Horizontal Scan") - if self.inMeasureOnlyMode: - self.HomingX = 0.0 - self.HomingY = 0.0 - self.HomingPosX += self.HomingScanDirection - if (self.HomingPosX == maxX + 1) or (self.HomingPosX == minX - 1): - if self.HomingPosX == maxX + 1: - self.HomingPosX = maxX - else: - self.HomingPosX = minX - self.HomingScanDirection *= -1 - self.HomingPosY -= 1 - if self.HomingPosY > maxY - 1: - self.HomingY -= 7.0 # drop down 7 mm for next square's guess (only) - self.HomeIn() - else: - self.inAutoMode = False - print("Calibration Completed") - # self.printCalibrationErrorValue() - else: # vertical - print("Vertical Scan") - if self.inMeasureOnlyMode: - self.HomingX = 0.0 - self.HomingY = 0.0 - self.HomingPosY -= self.HomingScanDirection - if (self.HomingPosY == maxY - 1) or (self.HomingPosY == minY + 1): - if self.HomingPosY == minY + 1: - self.HomingPosY = minY - else: - self.HomingPosY = maxY - self.HomingScanDirection *= -1 - self.HomingPosX += 1 - if self.HomingPosX != maxX + 1: - self.HomingY -= 7.0 # drop down 7 mm for next square's guess (only) - self.HomeIn() - else: - self.inAutoMode = False - print("Releasing Camera") - self.camera.release() - print("Calibration Completed") - - def on_Calibrate(self, args): - print("Initializing") - self.setCalibrationSettings(args) - print( - "Extents:" - + str(self.tlX) - + ", " - + str(self.tlY) - + " to " - + str(self.brX) - + ", " - + str(self.brY) - ) - if self.camera is None: - print("Starting Camera") - self.camera = cv2.VideoCapture(0) - print("Analyzing Images") - self.on_AutoHome(False) - return True diff --git a/Actions/triangularCalibration.py b/Actions/triangularCalibration.py index 3a109044..97802dc4 100644 --- a/Actions/triangularCalibration.py +++ b/Actions/triangularCalibration.py @@ -3,14 +3,25 @@ class TriangularCalibration(MakesmithInitFuncs): - def cutTestPaternTriangular(self): + + motorYoffsetEst = 0 + chainSagCorrectionEst = 0 + rotationRadiusEst = 0 + + def cutTriangularCalibrationPattern(self): + ''' + Sends command to controller to cut the calibration pattern. + :return: + ''' workspaceHeight = float( self.data.config.getValue("Maslow Settings", "bedHeight") ) workspaceWidth = float(self.data.config.getValue("Maslow Settings", "bedWidth")) - self.data.units = "MM" + # keep track of the units the machine is currently using to revert back if needed. + oldUnits = self.data.units + self.data.gcode_queue.put("G21 ") self.data.gcode_queue.put("G90 ") # Switch to absolute mode self.data.gcode_queue.put("G40 ") @@ -62,6 +73,13 @@ def cutTestPaternTriangular(self): self.data.gcode_queue.put("G90 ") # Switch back to absolute mode self.data.gcode_queue.put("G0 X0 Y0 ") # Move to home location + if oldUnits == "INCHES": + # switch back to inches + self.data.gcode_queue.put("G20 ") # Switch back to inches + + return True + + def calculate(self, result): """ Takes the measured distance and uses it to iteratively calculate the rotationDiskRadius and yMotorOffset @@ -76,7 +94,7 @@ def calculate(self, result): try: distBetweenCuts12 = float(result["cut12"]) - print(distBetweenCuts12) + self.data.console_queue.put(distBetweenCuts12) except: self.data.message_queue.put( "Message: Please enter a number for the distance between cut 1 and cut 2." @@ -85,7 +103,7 @@ def calculate(self, result): try: distBetweenCuts34 = float(result["cut34"]) - print(distBetweenCuts34) + self.data.console_queue.put(distBetweenCuts34) except: self.data.message_queue.put( "Message: Please enter a number for the distance between cut 3 and cut 4." @@ -94,7 +112,7 @@ def calculate(self, result): try: distWorkareaTopToCut5 = float(result["cut5"]) - print(distWorkareaTopToCut5) + self.data.console_queue.put(distWorkareaTopToCut5) except: self.data.message_queue.put( "Message: Please enter a number for the distance between the top of the work area and cut 5." @@ -103,33 +121,13 @@ def calculate(self, result): try: bitDiameter = float(result["bitDiameter"]) - print(bitDiameter) + self.data.console_queue.put(bitDiameter) except: self.data.message_queue.put( "Message: Please enter a number for the bit diameter." ) return False - """ - if self.unitsBtnT.text == 'Units: inches': - if (((distBetweenCuts12*25.4) > workspaceWidth) or ((distBetweenCuts12*25.4) < (workspaceWidth / 2))): - self.data.message_queue.put('Message: The measurement between cut 1 and cut 2 of ' + str(distBetweenCuts12) + ' inches seems wrong.\n\nPlease check the number and enter it again.') - return - if (((distBetweenCuts34*25.4) > workspaceWidth) or ((distBetweenCuts34*25.4) < (workspaceWidth / 2))): - self.data.message_queue.put('Message: The measurement between cut 3 and cut 4 of ' + str(distBetweenCuts34) + ' inches seems wrong.\n\nPlease check the number and enter it again.') - return - if (((distWorkareaTopToCut5*25.4) > (workspaceHeight/2)) or (distWorkareaTopToCut5 < 0)): - self.data.message_queue.put('Message: The measurement between the top edge of the work area and cut 5 of ' + str(distWorkareaTopToCut5) + ' inches seems wrong.\n\nPlease check the number and enter it again.') - return - if ((bitDiameter > 1) or (bitDiameter < 0)): - self.data.message_queue.put('Message: The bit diameter value of ' + str(bitDiameter) + ' inches seems wrong.\n\nPlease check the number and enter it again.') - return - distBetweenCuts12 *= 25.4 - distBetweenCuts34 *= 25.4 - distWorkareaTopToCut5 *= 25.4 - bitDiameter *= 25.4 - else: - """ if True: if (distBetweenCuts12 > workspaceWidth) or ( distBetweenCuts12 < (workspaceWidth / 2) @@ -329,8 +327,8 @@ def calculate(self, result): # Set up the iterative algorithm - print("Previous machine parameters:") - print( + self.data.console_queue.put("Previous machine parameters:") + self.data.console_queue.put( "Motor Spacing: " + str(motorSpacing) + ", Motor Y Offset: " @@ -351,7 +349,7 @@ def calculate(self, result): ChainErrorCut4 = acceptableTolerance n = 0 - print("Iterating for new machine parameters") + self.data.console_queue.put("Iterating for new machine parameters") # Iterate until error tolerance is achieved or maximum number of iterations occurs @@ -517,7 +515,7 @@ def calculate(self, result): motorYcoordEst - distWorkareaTopToCut5 - (bitDiameter / 2) - 12.7 ) - print( + self.data.console_queue.put( "N: " + str(n) + ", Motor Spacing: " @@ -529,7 +527,7 @@ def calculate(self, result): + ", Chain Sag Correction Value: " + str(round(chainSagCorrectionEst, 6)) ) - print( + self.data.console_queue.put( " Chain Error Cut 1: " + str(round(ChainErrorCut1, 4)) + ", Chain Error Cut 2: " @@ -578,22 +576,17 @@ def calculate(self, result): chainSagCorrectionCorrectionScale / 2 ) cutYoffsetCorrectionScale = float(cutYoffsetCorrectionScale / 2) - print("Estimated values out of range, trying again with smaller steps") + self.data.console_queue.put("Estimated values out of range, trying again with smaller steps") if n == numberOfIterations: - self.data.message_queue.put( + self.data.ui_queue1.put("Alert", "Alert", "Message: The machine was not able to be calibrated. Please ensure the work area dimensions are correct and try again." ) - print("Machine parameters could not be determined") + self.data.console_queue.put("Machine parameters could not be determined") return False - # self.horzMeasureT1.disabled = True - # self.horzMeasureT2.disabled = True - # self.vertMeasureT1.disabled = True - # self.enterValuesT.disabled = True - - print("Machine parameters found:") + self.data.console_queue.put("Machine parameters found:") motorYoffsetEst = ( motorYcoordEst - distWorkareaTopToCut5 - (bitDiameter / 2) - 12.7 @@ -603,7 +596,7 @@ def calculate(self, result): rotationRadiusEst = round(rotationRadiusEst, 1) chainSagCorrectionEst = round(chainSagCorrectionEst, 6) - print( + self.data.console_queue.put( "Motor Spacing: " + str(motorSpacing) + ", Motor Y Offset: " @@ -614,19 +607,10 @@ def calculate(self, result): + str(chainSagCorrectionEst) ) - # Update machine parameters - """ - self.data.config.setValue('Maslow Settings', 'motorOffsetY', str(motorYoffsetEst)) - self.data.config.setValue('Advanced Settings', 'rotationRadius', str(rotationRadiusEst)) - self.data.config.setValue('Advanced Settings', 'chainSagCorrection', str(chainSagCorrectionEst)) - - # With new calibration parameters return sled to workspace center + self.motorYoffsetEst = motorYoffsetEst + self.rotationRadiusEst = rotationRadiusEst + self.chainSagCorrectionEst = chainSagCorrectionEst - self.data.gcode_queue.put("G21 ") - self.data.gcode_queue.put("G90 ") - self.data.gcode_queue.put("G40 ") - self.data.gcode_queue.put("G0 X0 Y0 ") - """ return ( motorYoffsetEst, rotationRadiusEst, @@ -634,11 +618,18 @@ def calculate(self, result): cut34YoffsetEst, ) + def acceptTriangularCalibrationResults(self): + ''' + Saves the values that were calculated. + :return: + ''' + self.data.config.setValue('Maslow Settings', 'motorOffsetY', str(self.motorYoffsetEst)) + self.data.config.setValue('Advanced Settings', 'rotationRadius', str(self.rotationRadiusEst)) + self.data.config.setValue('Advanced Settings', 'chainSagCorrection', str(self.chainSagCorrectionEst)) + + self.data.gcode_queue.put("G21 ") + self.data.gcode_queue.put("G90 ") + self.data.gcode_queue.put("G40 ") + self.data.gcode_queue.put("G0 X0 Y0 ") + return True -""" - def switchUnitsT(self): - if self.unitsBtnT.text == 'Units: mm': - self.unitsBtnT.text = 'Units: inches' - else: - self.unitsBtnT.text = 'Units: mm' -""" diff --git a/Background/LogStreamer.py b/Background/LogStreamer.py new file mode 100644 index 00000000..5830123f --- /dev/null +++ b/Background/LogStreamer.py @@ -0,0 +1,46 @@ +from __main__ import socketio + +import time + +''' +This class sends logs to a browser via sockets. It monitors two log queues (log and alog) and sends the messages +if data is available. + +This class is not MakesmithInitFuncs inherited, so it doesn't have direct access to the data. Therefore, it gets +passed the app. +''' +class LogStreamer: + app = None + + def start(self, _app): + self.app = _app + self.app.data.console_queue.put("Starting Log Streamer") + + timeSinceLastLoggerState = time.time() + with self.app.app_context(): + while True: + # this sleep function is needed to keep it non-blocking. + time.sleep(0.001) + # if there is new data to be read + loggerState = self.app.data.logger.getLoggerState() + while (not self.app.data.alog_streamer_queue.empty() or not self.app.data.log_streamer_queue.empty()): + # process a line from the alog queue + if not self.app.data.alog_streamer_queue.empty(): + message = self.app.data.alog_streamer_queue.get() + if message != "": + socketio.emit("message", {"log": "alog", "data": message, "state": loggerState, + "dataFormat": "text"}, namespace="/MaslowCNCLogs", ) + timeSinceLastLoggerState = time.time() + # process a line from the log queue + if not self.app.data.log_streamer_queue.empty(): + message = self.app.data.log_streamer_queue.get() + if message != "": + socketio.emit("message", {"log": "log", "data": message, "state": loggerState, + "dataFormat": "text"}, namespace="/MaslowCNCLogs", ) + timeSinceLastLoggerState = time.time() + currentTime = time.time() + if currentTime - timeSinceLastLoggerState > 5: + socketio.emit("message", {"log": "state", "state": loggerState, "dataFormat":"text"}, + namespace="/MaslowCNCLogs", ) + timeSinceLastLoggerState = currentTime + diff --git a/Background/UIProcessor.py b/Background/UIProcessor.py index 8184f86d..54147e75 100644 --- a/Background/UIProcessor.py +++ b/Background/UIProcessor.py @@ -3,120 +3,168 @@ import time import math import json +import psutil +import webbrowser +from flask import render_template +''' +This class sends messages the browser via sockets. It monitors the ui_controller_queue (where controller messages that +need to be sent to the UI are put) and the ui_queue1 (where webcontrol-initiated messages that need to be sent to the UI +are put). There is a legacy ui_queue (not the missing 1) that I reworked into ui_queue1 but I never refactored. -class UIProcessor: +This class is not MakesmithInitFuncs inherited, so it doesn't have direct access to the data. Therefore, it gets +passed the app. +''' +class UIProcessor: app = None + lastCameraTime = 0 + lastHealthCheck = 0 + previousUploadFlag = None + previousCurrentTool = None + previousPositioningMode = None def start(self, _app): self.app = _app + self.app.data.console_queue.put("starting UI") with self.app.app_context(): while True: time.sleep(0.001) - if self.app.data.opticalCalibrationImageUpdated is True: - self.sendCalibrationMessage( - "OpticalCalibrationImageUpdated", - self.app.data.opticalCalibrationImage, - ) - self.app.data.opticalCalibrationImageUpdated = False + # send health message + self.performHealthCheck() + # send status message + self.performStatusCheck() + # send message to UI client if this is the first time webcontrol is being run. + if self.app.data.config.firstRun: + self.app.data.config.firstRun = False + # I *think* this was added to give time for the browser to open up. + time.sleep(2) + self.activateModal("Notification:", + "New installation detected. If you have an existing groundcontrol.ini file you would like to import, please do so now by pressing Actions->Import groundcontrol.ini file before doing anything else.", + "notification") + # This sends an updated camera image if available (camera) + if self.app.data.cameraImageUpdated is True: + if time.time() - self.lastCameraTime > .25: + self.sendCameraMessage( + "cameraImageUpdated", + self.app.data.cameraImage, + ) + self.app.data.cameraImageUpdated = False + self.lastCameraTime = time.time() + # function is run while queues are not empty while ( - not self.app.data.ui_queue.empty() - ): # if there is new data to be read - message = self.app.data.ui_queue.get() - # send message to web for display in appropriate column - if message != "": - if message[0] != "[" and message[0] != "<": - self.sendControllerMessage(message) - if message[0] == "<": - # print message - self.setPosOnScreen(message) - elif message[0] == "[": - if message[1:4] == "PE:": - # todo: - oo = 1 - # app.setErrorOnScreen(message) - elif message[0:8] == "Message:": - if message.find("adjust Z-Axis") != -1: - print("found adjust Z-Axis in message") - socketio.emit( - "requestedSetting", - {"setting": "pauseButtonSetting", "value": "Resume"}, - namespace="/MaslowCNC", - ) - self.activateModal("Notification:", message[9:]) - elif message[0:7] == "Action:": - if message.find("unitsUpdate") != -1: - units = self.app.data.config.getValue( - "Computed Settings", "units" - ) - socketio.emit( - "requestedSetting", - {"setting": "units", "value": units}, - namespace="/MaslowCNC", - ) - if message.find("gcodeUpdate") != -1: - socketio.emit( - "gcodeUpdate", - { - "data": json.dumps( - [ - ob.__dict__ - for ob in self.app.data.gcodeFile.line - ] - ) - }, - namespace="/MaslowCNC", - ) - if message.find("setAsPause") != -1: - socketio.emit( - "requestedSetting", - {"setting": "pauseButtonSetting", "value": "Pause"}, - namespace="/MaslowCNC", - ) - if message.find("setAsResume") != -1: - socketio.emit( - "requestedSetting", - {"setting": "pauseButtonSetting", "value": "Resume"}, - namespace="/MaslowCNC", - ) - if message.find("positionUpdate") != -1: - msg = message.split( - "_" - ) # everything to the right of the "_" should be the position data already json.dumps'ed - socketio.emit( - "positionMessage", - {"data": msg[1]}, - namespace="/MaslowCNC", - ) - if message.find("updatePorts") != -1: - ports = json.dumps(self.app.data.comPorts) - socketio.emit( - "updatePorts", {"data": ports}, namespace="/MaslowCNC" - ) - elif message[0:6] == "ALARM:": - self.activateModal("Notification:", message[7:]) - elif message == "ok\r\n": - pass # displaying all the 'ok' messages clutters up the display - else: - print(message) + not self.app.data.ui_controller_queue.empty() or not self.app.data.ui_queue1.empty()): # if there is new data to be read + # ui_controller_queue are messages from the controller. + if not self.app.data.ui_controller_queue.empty(): + message = self.app.data.ui_controller_queue.get() + if message != "": + if message[0] == "<": + #call function to parse position message and update UI clients + self.setPosOnScreen(message) + elif message[0] == "[": + # call function to parse position error message and update UI clients + if message[1:4] == "PE:": + self.setErrorOnScreen(message) + elif message[0:13] == "Maslow Paused": + # Maslow has been paused. set uploadFlag to 0 and update the pause button on the + # UI clients. In reality, uploadFlag should already be set to 0 by serialPortThread + # that is, the controller shouldn't be pausing without webcontrol already know it's + # going to pause. + self.app.data.uploadFlag = 0 + # Send '~' upon receiveing the "Maslow Paused" notification. This + # operation is to issue this 'un-pause' command which then lets two ok's to come back + # (one for the tool change and one for the ~) Without this, serialThread won't see + # that the bufferSize = bufferSpace and therefore won't issue any commands. + ## new stuff + # self.app.data.quick_queue.put("~") + ## end new stuff + self.app.data.pausedUnits = self.app.data.units + data = json.dumps({"setting": "pauseButtonSetting", "value": "Resume"}) + socketio.emit("message", + {"command": "requestedSetting", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", ) + elif message[0:12] == "Tool Change:": + # Tool change message detected. + # not sure what manualzaxisadjust is.. ### + self.app.data.manualZAxisAdjust = True + # keep track of whether upload flag was set... can't remember why. + self.app.data.previousUploadStatus = self.app.data.uploadFlag + # remember the current z value so it can be returned to. + self.app.data.pausedzval = self.app.data.zval + # remember the current units because user might switch them to zero the zaxis. + self.app.data.pausedUnits = self.app.data.units + # Remember current positioning mode. + self.app.data.pausedPositioningMode = self.app.data.positioningMode + self.app.data.console_queue.put("found tool change in message") + # send unpause + self.app.data.quick_queue.put("~") + # notify user + self.activateModal("Notification:", message[13:], "notification", resume="resume") + elif message[0:8] == "Message:": + # message received from controller + if message.find("adjust Z-Axis") != -1: + # manual z-axis adjustment requested. + self.app.data.console_queue.put("found adjust Z-Axis in message") + self.app.data.pausedUnits = self.app.data.units + self.activateModal("Notification:", message[9:], "notification", resume="resume") + elif message.find("Unable to find valid") != -1: + # position alarm detected.. chain lengths do not allow for forward kinematic. + # This could occur during the set sprockets to zero process.. so ignore alarm + # if either sprocket distance is zero. + if not self.isChainLengthZero(message): + self.sendAlarm(message); + else: + # something other than above.. + self.activateModal("Notification:", message[9:], "notification") + elif message[0:6] == "ALARM:": + # alarm received from controller + if message.find("The sled is not keeping up") != -1: + self.sendAlarm("Alarm: Sled Not Keeping Up") + elif message.find("Position Lost") != -1: + self.sendAlarm("Alarm: Position Lost. Reset Chains.") + else: + self.sendAlarm(message); + elif message[0:6] == "Unable to": + # not sure what this is for.. probably legacy or something.. TODO: cleanup + if message.find("The sled is not keeping up") != -1: + pass + self.sendAlarm("Alarm: Sled Not Keeping Up") + elif message == "ok\r\n": + pass # displaying all the 'ok' messages clutters up the display + else: + #if something else, send it to the UI to figure out. + self.sendControllerMessage(message) + if not self.app.data.ui_queue1.empty(): + # webcontrol generated messages to be sent to UI client + message = self.app.data.ui_queue1.get() + self.processMessage(message) def setPosOnScreen(self, message): + ''' + Parses the controller message and determines x,y,z coordinates of sled. + Based on ground control's implementation. Added a few hooks for the state. + :param message: + :return: + ''' try: with self.app.app_context(): startpt = message.find("MPos:") + 5 endpt = message.find("WPos:") numz = message[startpt:endpt] - units = "mm" # message[endpt+1:endpt+3] valz = numz.split(",") + state = "" + if message.find("Stop") != -1: + state = "Stopped" + elif message.find("Pause") != -1: + state = "Paused" + elif message.find("Idle") != -1: + state = "Idle" self.app.data.xval = float(valz[0]) self.app.data.yval = float(valz[1]) self.app.data.zval = float(valz[2]) - # print "x:"+str(app.data.xval)+", y:"+str(app.data.yval)+", z:"+str(app.data.zval) - if math.isnan(self.app.data.xval): self.sendControllerMessage("Unable to resolve x Kinematics.") self.app.data.xval = 0 @@ -126,33 +174,450 @@ def setPosOnScreen(self, message): if math.isnan(self.app.data.zval): self.sendControllerMessage("Unable to resolve z Kinematics.") self.app.data.zval = 0 + except: - print("One Machine Position Report Command Misread") + self.app.data.console_queue.put("One Machine Position Report Command Misread") return - position = { - "xval": self.app.data.xval, - "yval": self.app.data.yval, - "zval": self.app.data.zval, - } - self.sendPositionMessage(position) + # compute just how much the sled has moved. + xdiff = abs(self.app.data.xval - self.app.data.xval_prev) + ydiff = abs(self.app.data.yval - self.app.data.yval_prev) + zdiff = abs(self.app.data.zval - self.app.data.zval_prev) - def activateModal(self, title, message): - socketio.emit( - "activateModal", - {"title": title, "message": message}, - namespace="/MaslowCNC", - ) + # compute percentage of gcode that's been completed. + percentComplete = '%.1f' % math.fabs(100 * (self.app.data.gcodeIndex / (len(self.app.data.gcode) - 1))) + "%" + + # if the sled has moved more than a very, very small amount, then go ahead and send. Cuts down on network + # traffic. + if (xdiff + ydiff + zdiff) > 0.01: + # package as json + position = { + "xval": self.app.data.xval, + "yval": self.app.data.yval, + "zval": self.app.data.zval, + "pcom": percentComplete, + "state": state + } + # call command to send the position data + self.sendPositionMessage(position) + # keep track of position + self.app.data.xval_prev = self.app.data.xval + self.app.data.yval_prev = self.app.data.yval + self.app.data.zval_prev = self.app.data.zval + + def setErrorOnScreen(self, message): + ''' + Parses the error message and sends to UI clients. Allows for option to perform forward kinematics to see + where the router actually is based upon chain length errors. Not sure if particularly useful, but its an option + :param message: + :return: + ''' + limit = float(self.app.data.config.getValue("Advanced Settings", "positionErrorLimit")) + computedEnabled = int(self.app.data.config.getValue("WebControl Settings", "computedPosition")) + if limit != 0: + try: + with self.app.app_context(): + startpt = message.find(':') + 1 + endpt = message.find(',', startpt) + leftErrorValueAsString = message[startpt:endpt] + self.app.data.leftError = float(leftErrorValueAsString) / limit + + startpt = endpt + 1 + endpt = message.find(',', startpt) + rightErrorValueAsString = message[startpt:endpt] + self.app.data.rightError = float(rightErrorValueAsString) / limit + + # the two custom firmwares were modified to send the chain lengths as well as the error. This + # allows for forward kinematics to be performed to get sled location. + if self.app.data.controllerFirmwareVersion > 50 and self.app.data.controllerFirmwareVersion < 150: + + startpt = endpt + 1 + endpt = message.find(',', startpt) + bufferSizeValueAsString = message[startpt:endpt] + self.app.data.bufferSize = int(bufferSizeValueAsString) + + startpt = endpt + 1 + endpt = message.find(',', startpt) + leftChainLengthAsString = message[startpt:endpt] + self.app.data.leftChain = float(leftChainLengthAsString) + + startpt = endpt + 1 + endpt = message.find(']', startpt) + rightChainLengthAsString = message[startpt:endpt] + self.app.data.rightChain = float(rightChainLengthAsString) + + else: + # if not custom firmware, then just buffer size remains. + startpt = endpt + 1 + endpt = message.find(']', startpt) + bufferSizeValueAsString = message[startpt:endpt] + self.app.data.bufferSize = int(bufferSizeValueAsString) + # regardless of setting, if not custom firmware there cannot be a forward kinematic compute + computedEnabled = 0 + + if computedEnabled > 0: + self.app.data.computedX, self.app.data.computedY = self.app.data.holeyKinematics.forward( + self.app.data.leftChain, self.app.data.rightChain, self.app.data.xval, self.app.data.yval) + else: + # the -999999 value tells the UI client to ignore the data. + self.app.data.computedX = -999999 + self.app.data.computedY = -999999 + + # sets bad error values to zero. Not sure if needed anymore. + if math.isnan(self.app.data.leftError): + self.app.data.leftErrorValue = 0 + if math.isnan(self.app.data.rightError): + self.app.data.rightErrorValue = 0 + + except: + self.app.data.console_queue.put("One Error Report Command Misread") + return + + # only send the error information if it has changed at least slightly. + leftDiff = abs(self.app.data.leftError - self.app.data.leftError_prev) + rightDiff = abs(self.app.data.rightError - self.app.data.rightError_prev) + + if (leftDiff + rightDiff) >= 0.001: + errorValues = { + "leftError": abs(self.app.data.leftError), + "rightError": abs(self.app.data.rightError), + "computedX": self.app.data.computedX, + "computedY": self.app.data.computedY, + "computedEnabled": computedEnabled + } + self.sendErrorValueMessage(errorValues) + self.app.data.leftError_prev = self.app.data.leftError + self.app.data.rightError_prev = self.app.data.rightError + + def activateModal(self, title, message, modalType, resume="false", progress="false"): + ''' + Sends socket message to UI client to activate a modal + :param title: Title to be used for the modal + :param message: The message that should appear in the modal body + :param modalType: The type of modal (content, notification, alarm).. I don't think content modals come via this + fucntion because modalSize is hardcoded to small. + :param resume: Whether to have a resume button on the modal.. used while gcode is running + :param progress: Whether to show the progress bar/spinner + :return: + ''' + data = json.dumps( + {"title": title, "message": message, "resume": resume, "progress": progress, "modalSize": "small", + "modalType": modalType}) + socketio.emit("message", {"command": "activateModal", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", + ) + + def sendAlarm(self, message): + ''' + Sends an alarm to the UI client via socket. Alarms display as a scrolling marque on right side of screen. + :param message: + :return: + ''' + data = json.dumps({"message": message}) + socketio.emit("message", {"command": "alarm", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", + ) def sendControllerMessage(self, message): - socketio.emit("controllerMessage", {"data": message}, namespace="/MaslowCNC") + ''' + Sends a message from the controller to the UI client. This occurs for messages that aren't processed by + webcontrol in the main UI Processor loop. + :param message: + :return: + ''' + socketio.emit("message", {"command": "controllerMessage", "data": json.dumps(message), "dataFormat": "json"}, + namespace="/MaslowCNC") + + def sendWebMCPMessage(self, message): + ''' + Seems to just send a shutdown message to webmcp.. everything else appears to be commented out. + :param message: + :return: + ''' + # print(message) + # socketio.emit("message", {"command": json.dumps(message), "dataFormat": "json"},namespace="/WebMCP") + socketio.emit("shutdown", namespace="/WebMCP") def sendPositionMessage(self, position): + ''' + Sends the position message to UI client. Not sure why I separated this from the only function that calls it. + :param position: + :return: + ''' + socketio.emit("message", {"command": "positionMessage", "data": json.dumps(position), "dataFormat": "json"}, + namespace="/MaslowCNC") + + def sendErrorValueMessage(self, position): + ''' + Sends the error value message to UI client. Not sure why I separated this from the only function that calls it. + :param position: + :return: + ''' + socketio.emit("message", {"command": "errorValueMessage", "data": json.dumps(position), "dataFormat": "json"}, + namespace="/MaslowCNC") + + def sendCameraMessage(self, message, _data=""): + ''' + Sends message to the UI client regarding camera.. message could be to turn camera display on or off, or to + update the camera display. + :param message: + :param _data: + :return: + ''' + data = json.dumps({"command": message, "data": _data}) socketio.emit( - "positionMessage", {"data": json.dumps(position)}, namespace="/MaslowCNC" + "message", {"command": "cameraMessage", "data": data, "dataFormat": "json"}, namespace="/MaslowCNC" ) - def sendCalibrationMessage(self, message, data): + def updatePIDData(self, message, _data=""): + ''' + Sends PID test data to UI client. + :param message: + :param _data: + :return: + ''' + data = json.dumps({"command": message, "data": _data}) socketio.emit( - "calibrationMessage", {"msg": message, "data": data}, namespace="/MaslowCNC" + "message", {"command": "updatePIDData", "data": data, "dataFormat": "json"}, namespace="/MaslowCNC" + ) + + def sendGcodeUpdate(self): + ''' + Sends the gcode display data to the UI client. Originally this was sent uncompressed but later I added + compression to speed up the transmisison process. + :return: + ''' + if self.app.data.compressedGCode3D is not None: + self.app.data.console_queue.put("Sending Gcode compressed") + # turn on spinner on UI clients + socketio.emit("message", {"command": "showFPSpinner", + "data": len(self.app.data.compressedGCode3D), "dataFormat": "int"}, + namespace="/MaslowCNC", ) + # pause to let the spinner get turned on. + time.sleep(0.25) + # send the data. Once processed by the UI client, the client will turn off the spinner. + socketio.emit("message", {"command": "gcodeUpdateCompressed", + "data": self.app.data.compressedGCode3D, "dataFormat": "base64"}, + namespace="/MaslowCNC", ) + self.app.data.console_queue.put("Sent Gcode compressed") + else: + #send "" if there is no compressed data (i.e., because there's no gcode to compress) + socketio.emit("message", {"command": "gcodeUpdateCompressed", + "data": "", "dataFormat": "base64"}, + namespace="/MaslowCNC", ) + + def sendBoardUpdate(self): + ''' + Sends board information including cutdata. boardData is dimensions, material, ID. cutData is an array that + defines the area that has been cut. + :return: + ''' + boardData = self.app.data.boardManager.getCurrentBoard().getBoardInfoJSON() + if boardData is not None: + self.app.data.console_queue.put("Sending Board Data") + socketio.emit("message", {"command": "boardDataUpdate", + "data": boardData, "dataFormat": "json"}, + namespace="/MaslowCNC", ) + self.app.data.console_queue.put("Sent Board Data") + + cutData = self.app.data.boardManager.getCurrentBoard().getCompressedCutData() + if True: # cutData is not None: + self.app.data.console_queue.put("Sending Board Cut Data compressed") + socketio.emit("message", {"command": "showFPSpinner", + "data": 1, "dataFormat": "int"}, + namespace="/MaslowCNC", ) + time.sleep(0.25) + socketio.emit("message", {"command": "boardCutDataUpdateCompressed", + "data": cutData, "dataFormat": "base64"}, + namespace="/MaslowCNC", ) + self.app.data.console_queue.put("Sent Board Cut Data compressed") + + def unitsUpdate(self): + ''' + Sends the units in use to the UI Client. + :return: + ''' + units = self.app.data.config.getValue( + "Computed Settings", "units" + ) + data = json.dumps({"setting": "units", "value": units}) + socketio.emit("message", {"command": "requestedSetting", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", ) + + def distToMoveUpdate(self): + ''' + Sends the value to populate the distance to move on the frontpage. + :return: + ''' + distToMove = self.app.data.config.getValue( + "Computed Settings", "distToMove" + ) + data = json.dumps({"setting": "distToMove", "value": distToMove}) + socketio.emit("message", {"command": "requestedSetting", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", ) + + def unitsUpdateZ(self): + ''' + Sends the z-units in use to the UI client + :return: + ''' + unitsZ = self.app.data.config.getValue( + "Computed Settings", "unitsZ" + ) + data = json.dumps({"setting": "unitsZ", "value": unitsZ}) + socketio.emit("message", {"command": "requestedSetting", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", ) + + def distToMoveUpdateZ(self): + ''' + Sends the value to populate the distance to move on the z-axis popup. + :return: + ''' + distToMoveZ = self.app.data.config.getValue( + "Computed Settings", "distToMoveZ" ) + data = json.dumps({"setting": "distToMoveZ", "value": distToMoveZ}) + socketio.emit("message", {"command": "requestedSetting", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", ) + + def processMessage(self, _message): + ''' + This function process all the webcontrol initiated ui_queue1 messages. I separated this because the main queue + function was getting annoyingly big. it basically just calls the function that has been requested. + :param _message: a json containing the message + :return: + ''' + # parse the message to get to its components + msg = json.loads(_message) + if msg["command"] == "WebMCP": + self.sendWebMCPMessage(msg["message"]) + if msg["command"] == "SendAlarm": + self.sendAlarm(msg["message"]) + if msg["command"] == "Action": + if msg["message"] == "gcodeUpdate": + self.sendGcodeUpdate() + elif msg["message"] == "boardUpdate": + self.sendBoardUpdate() + elif msg["message"] == "unitsUpdate": + self.unitsUpdate() + elif msg["message"] == "distToMoveUpdate": + self.distToMoveUpdate() + elif msg["message"] == "unitsUpdateZ": + self.unitsUpdateZ() + elif msg["message"] == "distToMoveUpdateZ": + self.distToMoveUpdateZ() + elif msg["message"] == "updateTimer": + # Todo: clean this up .. edit: sendCalibrationMessage got deleted somewhere. + #self.sendCalibrationMessage("updateTimer", json.loads(msg["data"])) + pass + elif msg["message"] == "updateCamera": + self.sendCameraMessage("updateCamera", json.loads(msg["data"])) + elif msg["message"] == "updatePIDData": + self.updatePIDData("updatePIDData", json.loads(msg["data"])) + elif msg["message"] == "clearAlarm": + msg["data"] = json.dumps({"data": ""}) + socketio.emit("message", {"command": msg["message"], "data": msg["data"], "dataFormat": "json"}, + namespace="/MaslowCNC") + # I'm pretty sure this can be cleaned up into just a continuation of elif's + else: + if msg["message"] == "setAsPause": + msg["message"] = "requestedSetting" + msg["data"] = json.dumps({"setting": "pauseButtonSetting", "value": "Pause"}) + elif msg["message"] == "setAsResume": + msg["message"] = "requestedSetting" + msg["data"] = json.dumps({"setting": "pauseButtonSetting", "value": "Resume"}) + elif msg["message"] == "updatePorts": + msg["data"] = json.dumps(self.app.data.comPorts) + elif msg["message"] == "closeModals": + title = json.loads(msg["data"]) + msg["data"] = json.dumps({"title": title}) # msg["data"]}) + socketio.emit("message", {"command": msg["message"], "data": msg["data"], "dataFormat": "json"}, + namespace="/MaslowCNC") + # I think I was working on clearing on an issue with the formatting of messages so I added this. I think the + # only function that calls it is the serialPortThread when webcontrol connects to the arduino. + elif msg["command"] == "TextMessage": + socketio.emit("message", {"command": "controllerMessage", "data": msg["data"], "dataFormat": "json"}, + namespace="/MaslowCNC") + # Alerts activate the modal. If alerts are sent on top of each other, it can mess up the UI client display. + elif msg["command"] == "Alert": + self.activateModal(msg["message"], msg["data"], "alert") + elif msg["command"] == "SpinnerMessage": + self.activateModal("Notification:", msg["data"], "notification", progress="spinner") + + def sendCalibrationImage(self, message, _data): + ''' + Sends the calibration image (either an image or the test image) + :param message: + :param _data: + :return: + ''' + + data = json.dumps({"command": message, "data": _data}) + + socketio.emit( + "message", {"command": "updateCalibrationImage", "data": data, "dataFormat": "json"}, namespace="/MaslowCNC" + ) + + def performHealthCheck(self): + ''' + This function sends a message to the UI clients every 5 seconds. It contains cpuUsage, current bufferSize as + reported by the controller, and indication if the uploadFlag is enabled or disabled. The client prevents the + user from performing certain functions when the gcode is being sent (i.e., uploadFlag enabled). + :return: + ''' + currentTime = time.time() + if currentTime - self.lastHealthCheck > 5: + self.lastHealthCheck = currentTime + load = max(psutil.cpu_percent(interval=None, percpu=True)) + weAreBufferingLines = bool(int(self.app.data.config.getValue("Maslow Settings", "bufferOn"))) + if weAreBufferingLines: + bufferSize = self.app.data.bufferSize + else: + bufferSize = -1 + healthData = { + "cpuUsage": load, + "bufferSize": bufferSize, + } + socketio.emit("message", {"command": "healthMessage", "data": json.dumps(healthData), "dataFormat": "json"}, + namespace="/MaslowCNC") + self.performStatusCheck(True) + + def performStatusCheck(self, healthCheckCalled=False): + ''' + This function sends a message to the client if it detects a change in the following parameters: + uploadFlag, positioningMode, currentTool + Also sends on every health check to get new connected clients in sync. + :return: + ''' + update = healthCheckCalled + if self.previousUploadFlag != self.app.data.uploadFlag: + update = True + self.previousUploadFlag = self.app.data.uploadFlag + if self.previousPositioningMode != self.app.data.positioningMode: + update = True + self.previousPositioningMode = self.app.data.positioningMode + if self.previousCurrentTool != self.app.data.currentTool: + update = True + self.previousCurrentTool = self.app.data.currentTool + + #print("positioning mode = "+str(self.app.data.positioningMode)) + + if update: + statusData = { + "uploadFlag": self.app.data.uploadFlag, + "positioningMode": self.app.data.positioningMode, + "currentTool": self.app.data.currentTool, + } + socketio.emit("message", + {"command": "statusMessage", "data": json.dumps(statusData), "dataFormat": "json"}, + namespace="/MaslowCNC") + + def isChainLengthZero(self, msg): + #Message: Unable to find valid machine position for chain lengths 0.00, 0.00 Left Chain Length + # If one chain length is zero, it will report as above. + if msg.find("lengths 0.00") != -1: + return True + if msg.find(", 0.00") != -1: + return True + return False + diff --git a/Background/WebMCPProcessor.py b/Background/WebMCPProcessor.py new file mode 100644 index 00000000..b82f511d --- /dev/null +++ b/Background/WebMCPProcessor.py @@ -0,0 +1,42 @@ +from __main__ import socketio +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs + +import time + +class WebMCPProcessor(MakesmithInitFuncs): + ''' + This class is deprecated as shifting away from WebMCP. + ''' + + app = None + + def start(self, _app): + print("Starting WebMCP Queue Processor") + self.app = _app + self.data.webMCPActive = True + while True: + time.sleep(0.001) + while (not self.data.mcp_queue.empty()): # if there is new data to be read + message = self.data.mcp_queue.get() + #print("MCP Queue:"+message) + if self.app is not None: + with self.app.app_context(): + #print("Emitting:"+message) + socketio.emit("webcontrolMessage", {"data": message}, namespace="/WebMCP") + + def connect(self, _app): + self.app = _app + +class ConsoleProcessor(MakesmithInitFuncs): + + def start(self): + print("Starting Console Queue Processor") + while True: + time.sleep(0.001) + while (not self.data.console_queue.empty()): # if there is new data to be read + message = self.data.console_queue.get() + print(message) + if self.data.webMCPActive: + #print("putting message in mcp_queue") + self.data.mcp_queue.put(message) + diff --git a/Background/controllerTask.py b/Background/controllerTask.py deleted file mode 100644 index 395c64bb..00000000 --- a/Background/controllerTask.py +++ /dev/null @@ -1,185 +0,0 @@ -import time -import math -import json - - -def background_stuff(app): - with app.app_context(): - while True: - time.sleep(0.001) - if app.data.opticalCalibrationImageUpdated is True: - sendCalibrationMessage( - "OpticalCalibrationImageUpdated", app.data.opticalCalibrationImage - ) - app.data.opticalCalibrationImageUpdated = False - while not app.data.message_queue.empty(): # if there is new data to be read - message = app.data.message_queue.get() - # send message to web for display in appropriate column - if message != "": - if message[0] != "[" and message[0] != "<": - sendControllerMessage(message) - if message[0] == "<": - # print message - setPosOnScreen(app, message) - elif message[0] == "$": - app.data.config.receivedSetting(message) - elif message[0] == "[": - if message[1:4] == "PE:": - # todo: - oo = 1 - # app.setErrorOnScreen(message) - elif message[1:8] == "Measure": - measuredDist = float(message[9 : len(message) - 3]) - try: - app.data.measureRequest(measuredDist) - except Exception as e: - print(e) - print("No function has requested a measurement") - elif message[0:13] == "Maslow Paused": - app.data.uploadFlag = 0 - print(message) - elif message[0:8] == "Message:": - if ( - app.data.calibrationInProcess - and message[0:15] == "Message: Unable" - ): # this suppresses the annoying messages about invalid chain lengths during the calibration process - break - app.previousUploadStatus = app.data.uploadFlag - app.data.uploadFlag = 0 - if message.find("adjust Z-Axis") != -1: - print("found adjust Z-Axis in message") - socketio.emit( - "requestedSetting", - {"setting": "pauseButtonSetting", "value": "Resume"}, - namespace="/MaslowCNC", - ) - activateModal("Notification:", message[9:]) - elif message[0:7] == "Action:": - if message.find("unitsUpdate") != -1: - units = app.data.config.getValue("Computed Settings", "units") - socketio.emit( - "requestedSetting", - {"setting": "units", "value": units}, - namespace="/MaslowCNC", - ) - if message.find("gcodeUpdate") != -1: - socketio.emit( - "gcodeUpdate", - { - "data": json.dumps( - [ob.__dict__ for ob in app.data.gcodeFile.line] - ) - }, - namespace="/MaslowCNC", - ) - if message.find("setAsPause") != -1: - socketio.emit( - "requestedSetting", - {"setting": "pauseButtonSetting", "value": "Pause"}, - namespace="/MaslowCNC", - ) - if message.find("setAsResume") != -1: - socketio.emit( - "requestedSetting", - {"setting": "pauseButtonSetting", "value": "Resume"}, - namespace="/MaslowCNC", - ) - if message.find("positionUpdate") != -1: - msg = message.split( - "_" - ) # everything to the right of the "_" should be the position data already json.dumps'ed - socketio.emit( - "positionMessage", {"data": msg[1]}, namespace="/MaslowCNC" - ) - elif message[0:6] == "ALARM:": - app.previousUploadStatus = app.data.uploadFlag - app.data.uploadFlag = 0 - activateModal("Notification:", message[7:]) - elif message[0:8] == "Firmware": - app.data.logger.writeToLog( - "Ground Control Version " + str(app.data.version) + "\n" - ) - print( - "Ground Control " - + str(app.data.version) - + "\r\n" - + message - + "\r\n" - ) - # Check that version numbers match - if float(message[-7:]) < float(app.data.version): - app.data.message_queue.put( - "Message: Warning, your firmware is out of date and may not work correctly with this version of Ground Control\n\n" - + "Ground Control Version " - + str(app.data.version) - + "\r\n" - + message - ) - if float(message[-7:]) > float(app.data.version): - app.data.message_queue.put( - "Message: Warning, your version of Ground Control is out of date and may not work with this firmware version\n\n" - + "Ground Control Version " - + str(app.data.version) - + "\r\n" - + message - ) - elif message == "ok\r\n": - pass # displaying all the 'ok' messages clutters up the display - else: - print(message) - - -def setPosOnScreen(app, message): - try: - with app.app_context(): - startpt = message.find("MPos:") + 5 - endpt = message.find("WPos:") - numz = message[startpt:endpt] - units = "mm" # message[endpt+1:endpt+3] - valz = numz.split(",") - - app.data.xval = float(valz[0]) - app.data.yval = float(valz[1]) - app.data.zval = float(valz[2]) - - # print "x:"+str(app.data.xval)+", y:"+str(app.data.yval)+", z:"+str(app.data.zval) - - if math.isnan(app.data.xval): - sendControllerMessage("Unable to resolve x Kinematics.") - app.data.xval = 0 - if math.isnan(app.data.yval): - sendControllerMessage("Unable to resolve y Kinematics.") - app.data.yval = 0 - if math.isnan(app.data.zval): - sendControllerMessage("Unable to resolve z Kinematics.") - app.data.zval = 0 - except: - print("One Machine Position Report Command Misread") - return - - position = {"xval": app.data.xval, "yval": app.data.yval, "zval": app.data.zval} - sendPositionMessage(position) - - -def activateModal(title, message): - socketio.emit( - "activateModal", {"title": title, "message": message}, namespace="/MaslowCNC" - ) - - -def sendControllerMessage(message): - socketio.emit("controllerMessage", {"data": message}, namespace="/MaslowCNC") - - -def sendPositionMessage(position): - socketio.emit( - "positionMessage", {"data": json.dumps(position)}, namespace="/MaslowCNC" - ) - - -def sendCalibrationMessage(message, data): - print("sending updated image") - # print(len(data)) - socketio.emit( - "calibrationMessage", {"msg": message, "data": data}, namespace="/MaslowCNC" - ) diff --git a/Background/messageProcessor.py b/Background/messageProcessor.py index a988bfb2..6f30bec8 100644 --- a/Background/messageProcessor.py +++ b/Background/messageProcessor.py @@ -11,78 +11,163 @@ class MessageProcessor(MakesmithInitFuncs): """ def start(self): + while True: + # give other threads opportunity to run time.sleep(0.001) - while ( - not self.data.message_queue.empty() - ): # if there is new data to be read + # check for available update file every hour. + if time.time()-self.data.lastChecked > 60*60: + self.data.lastChecked = time.time() + self.data.releaseManager.checkForLatestPyRelease() + self.data.helpManager.checkForUpdatedHelp() + # process messages while queue is not empty. Everything else is on hold until queue is cleared. + while ( not self.data.message_queue.empty() ): # if there is new data to be read message = self.data.message_queue.get() - # send message to web for display in appropriate column if message != "": - if message[0] != "[" and message[0] != "<": - self.data.ui_queue.put(message) - if message[0] == "<": - self.data.ui_queue.put(message) - elif message[0] == "$": - self.data.config.receivedSetting(message) - elif message[0] == "[": - if message[1:4] == "PE:": - # todo: - oo = 1 - # app.setErrorOnScreen(message) - elif message[1:8] == "Measure": - measuredDist = float(message[9 : len(message) - 3]) - try: - self.data.measureRequest(measuredDist) - except Exception as e: - print(e) - print("No function has requested a measurement") - elif message[0:13] == "Maslow Paused": - self.data.uploadFlag = 0 - print(message) - elif message[0:8] == "Message:": - if ( - self.data.calibrationInProcess - and message[0:15] == "Message: Unable" - ): # this suppresses the annoying messages about invalid chain lengths during the calibration process - break - self.data.previousUploadStatus = self.data.uploadFlag - self.data.uploadFlag = 0 - if message.find("adjust Z-Axis") != -1: - self.data.ui_queue.put(message) - elif message[0:6] == "ALARM:": - self.data.previousUploadStatus = self.data.uploadFlag - self.data.uploadFlag = 0 - self.data.ui_queue.put(message) - elif message[0:8] == "Firmware": - self.data.logger.writeToLog( - "Ground Control Version " + str(self.data.version) + "\n" - ) - print( - "Ground Control " - + str(self.data.version) - + "\r\n" - + message - + "\r\n" - ) - # Check that version numbers match - if float(message[-7:]) < float(self.data.version): - self.data.ui_queue.put( - "Message: Warning, your firmware is out of date and may not work correctly with this version of Ground Control\n\n" - + "Ground Control Version " - + str(self.data.version) - + "\r\n" - + message - ) - if float(message[-7:]) > float(self.data.version): - self.data.ui_queue.put( - "Message: Warning, your version of Ground Control is out of date and may not work with this firmware version\n\n" - + "Ground Control Version " - + str(self.data.version) - + "\r\n" - + message - ) - elif message == "ok\r\n": - pass # displaying all the 'ok' messages clutters up the display - else: - print(message) + if message[0] == "<": + # message to be processed by UIProcessor + self.data.ui_controller_queue.put(message) + elif message[0] == "$": + # setting received from controller + self.data.config.receivedSetting(message) + elif message[0] == "[": + # positional error or measurement message + if message[1:4] == "PE:": + # send to UIProcessor for processing + self.data.ui_controller_queue.put(message) + elif message[1:8] == "Measure": + # get distance and call the callback. + measuredDist = float(message[9 : len(message) - 3]) + try: + self.data.measureRequest(measuredDist) + except Exception as e: + self.data.console_queue.put(str(e)) + self.data.console_queue.put("No function has requested a measurement") + elif message[0:14] == "FAKE_SERVO off": + self.data.fakeServoStatus = False + self.data.console_queue.put(message) + elif message[0:13] == "FAKE_SERVO on": + self.data.fakeServoStatus = True + self.data.console_queue.put(message) + elif message[0:13] == "Maslow Paused": + # received controller-initiated pause message. Free controller to accept moves and send + # message to UIProcessor to process. + self.data.uploadFlag = 0 + self.data.ui_controller_queue.put(message) + elif message[0:8] == "Message:": + # suppress the annoying messages about invalid chain lengths during the calibration process + if (self.data.calibrationInProcess and message[0:15] == "Message: Unable"): + break + # track the previous uploadFlag and stop uploading. Likely am going to receive a message + # that requires a pause. + self.data.previousUploadStatus = self.data.uploadFlag + self.data.uploadFlag = 0 + if message.find("adjust Z-Axis") != -1: + # z-axis must not be enabled. Send message to UIProcessor for processing. + # set manualZAxisAdjust, but not sure its needed if manual adjustment is being used. + # Todo: cleanup if needed. + self.data.manualZAxisAdjust = True + self.data.ui_controller_queue.put(message) + if message[0:15] == "Message: Unable": + # received an error message from forward.kinematics that chain lengths don't resolve. + # send to UIProcessor for processing. + self.data.ui_controller_queue.put(message) + elif message[0:6] == "ALARM:": + # something bad happened, likley sled not keeping up. + # keep track of upload status, pause run, and send to UIProcessor for processing. + self.data.previousUploadStatus = self.data.uploadFlag + self.data.uploadFlag = 0 + self.data.ui_controller_queue.put(message) + elif message[0:8] == "Firmware": + ''' + send this alarm clear if Firmware is received. The thought is that if there is an alarm and + this message appears, then the connection to the arduino has been reset. + ''' + self.data.ui_queue1.put("Action", "clearAlarm", "") + + self.data.logger.writeToLog("Ground Control Version " + str(self.data.version) + "\n") + self.data.console_queue.put("WebControl " + str(self.data.version) + "\r\n" + message + "\r\n") + # Check that version numbers match + self.data.controllerFirmwareVersion = float(message[16-len(message):]) + tmpVersion = self.data.controllerFirmwareVersion + # <50 implies a stock firmware + if tmpVersion <50: + if self.data.stockFirmwareVersion is not None: + if tmpVersion < float(self.data.stockFirmwareVersion): + self.data.ui_queue1.put("Alert", "Alert", + "

Warning, you are running a stock firmware that is not up to date. This version may not work correctly with this version of WebControl.

" + + "

Please, click Actions->Upgrade Stock Firmware to update the controller to the latest WebControl-compatible code.

" + +"

WebControl:"+str(float(self.data.stockFirmwareVersion))+", Controller:"+str(tmpVersion)+"

" + ) + elif tmpVersion > float(self.data.stockFirmwareVersion): + self.data.ui_queue1.put("Alert", "Alert", + "

Warning, you are running a stock firmware that is newer than what is included in WebControl. This version may not work correctly with this version of WebControl.

" + +"

WebControl:"+str(float(self.data.stockFirmwareVersion))+", Controller:"+str(tmpVersion)+"

" + ) + # 50 <= x < 100 implies holey calibration firmware + if tmpVersion >= 50 and tmpVersion < 100: + if self.data.holeyFirmwareVersion is not None: + if tmpVersion < float(self.data.holeyFirmwareVersion): + self.data.ui_queue1.put("Alert", "Alert", + "

Warning, you are running a Holey Calibration firmware that is not up to date. This version may not work correctly with this version of WebControl.

" + + "

Please, click Actions->Upgrade Holey Firmware to update the controller to the latest WebControl-compatible code.

" + +"

WebControl:"+str(float(self.data.holeyFirmwareVersion))+", Controller:"+str(tmpVersion)+"

" + ) + elif tmpVersion > float(self.data.holeyFirmwareVersion): + self.data.ui_queue1.put("Alert", "Alert", + "

Warning, you are running a Holey Calibration firmware that is newer than what is included in WebControl. This version may not work correctly with this version of WebControl.

" + "

WebControl:"+str(float(self.data.holeyFirmwareVersion))+", Controller:"+str(tmpVersion)+"

" + ) + # x >= 100 implies optical calibration firmware + if tmpVersion >= 100: + if self.data.customFirmwareVersion is not None: + if tmpVersion < float(self.data.customFirmwareVersion): + self.data.ui_queue1.put("Alert", "Alert", + "

Warning, you are running a custom firmware that is not" + + " up to date. This version may not work correctly with" + + " this version of WebControl.

" + + "

Please, click Actions->Upgrade Custom Firmware to" + + " update the controller to the latest" + + " WebControl-compatible code.

" + + "

WebControl:" + + str(float(self.data.customFirmwareVersion)) + + ", Controller:"+str(tmpVersion)+"

" + ) + elif tmpVersion > float(self.data.customFirmwareVersion): + self.data.ui_queue1.put("Alert", "Alert", + "

Warning, you are running a custom firmware that is " + + "newer than what is included in WebControl. This version" + + " may not work correctly with this version of WebControl." + + "

WebControl:" + + str(float(self.data.customFirmwareVersion)) + + ", Controller:" + str(tmpVersion)+"

" + ) + + elif message == "ok\r\n": + pass # displaying all the 'ok' messages clutters up the display + + ### + ### Velocity PID Testing Processing + ### Watch for messages and log data + ### + elif message[0:26] == "--PID Velocity Test Stop--": + self.data.actions.velocityPIDTestRun("stop", "") + elif self.data.inPIDVelocityTest: + self.data.actions.velocityPIDTestRun("running", message) + elif message[0:27] == "--PID Velocity Test Start--": + self.data.actions.velocityPIDTestRun("start", "") + ### + ### Positional PID Testing Processing + ### Watch for messages and log data + ### + elif message[0:26] == "--PID Position Test Stop--": + self.data.actions.positionPIDTestRun("stop", "") + elif self.data.inPIDPositionTest: + self.data.actions.positionPIDTestRun("running", message) + elif message[0:27] == "--PID Position Test Start--": + self.data.actions.positionPIDTestRun("start", "") + + else: + # Just send it to the UIProcessor for processing. + self.data.ui_controller_queue.put(message) + diff --git a/Background/webcamVideoStream.py b/Background/webcamVideoStream.py index d0101739..dff3157f 100644 --- a/Background/webcamVideoStream.py +++ b/Background/webcamVideoStream.py @@ -1,41 +1,189 @@ -from threading import Thread -import cv2 +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs +import threading +#import cv2 +import time +import base64 -class WebcamVideoStream: +class WebcamVideoStream(MakesmithInitFuncs): + th = None + lastCameraRead = 0 + stopped = True + suspended = False + stream = None + height = 640 + width = 480 + fps = 5 + videoSize = "640x480" + cameraSleep = 0.01 + debugCamera = False + def __init__(self, src=0): # initialize the video camera stream and read the first frame # from the stream - self.stream = cv2.VideoCapture(src) - (self.grabbed, self.frame) = self.stream.read() + #self.stream = cv2.VideoCapture(src) + + + #(self.grabbed, self.frame) = self.stream.read() # initialize the variable used to indicate if the thread should # be stopped - self.stopped = False + #self.stopped = True + #self.suspended = False print("Camera initialized") - def start(self): + def getSettings(self, src=0): + cameraOff = False + #if self.stream is None: + #self.stream = cv2.VideoCapture(src) + #self.setVideoSize() + #self.setFPS() + #cameraOff = True + # if debugging, print camera values + ''' + if self.debugCamera: + self.data.console_queue.put("CAP_PROP_POS_MSEC=" + str(self.stream.get(cv2.CAP_PROP_POS_MSEC))) + self.data.console_queue.put("CAP_PROP_POS_FRAMES=" + str(self.stream.get(cv2.CAP_PROP_POS_FRAMES))) + self.data.console_queue.put("CAP_PROP_POS_AVI_RATIO=" + str(self.stream.get(cv2.CAP_PROP_POS_AVI_RATIO))) + self.data.console_queue.put("CAP_PROP_FRAME_WIDTH=" + str(self.stream.get(cv2.CAP_PROP_FRAME_WIDTH))) + self.data.console_queue.put("CAP_PROP_FRAME_HEIGHT=" + str(self.stream.get(cv2.CAP_PROP_FRAME_HEIGHT))) + self.data.console_queue.put("CAP_PROP_FPS=" + str(self.stream.get(cv2.CAP_PROP_FPS))) + self.data.console_queue.put("CAP_PROP_FOURCC=" + str(self.stream.get(cv2.CAP_PROP_FOURCC))) + self.data.console_queue.put("CAP_PROP_FRAME_COUNT=" + str(self.stream.get(cv2.CAP_PROP_FRAME_COUNT))) + self.data.console_queue.put("CAP_PROP_FORMAT=" + str(self.stream.get(cv2.CAP_PROP_FORMAT))) + self.data.console_queue.put("CAP_PROP_MODE=" + str(self.stream.get(cv2.CAP_PROP_MODE))) + self.data.console_queue.put("CAP_PROP_BRIGHTNESS=" + str(self.stream.get(cv2.CAP_PROP_BRIGHTNESS))) + self.data.console_queue.put("CAP_PROP_CONTRAST=" + str(self.stream.get(cv2.CAP_PROP_CONTRAST))) + self.data.console_queue.put("CAP_PROP_SATURATION=" + str(self.stream.get(cv2.CAP_PROP_SATURATION))) + self.data.console_queue.put("CAP_PROP_HUE=" + str(self.stream.get(cv2.CAP_PROP_HUE))) + self.data.console_queue.put("CAP_PROP_GAIN=" + str(self.stream.get(cv2.CAP_PROP_GAIN))) + self.data.console_queue.put("CAP_PROP_EXPOSURE=" + str(self.stream.get(cv2.CAP_PROP_EXPOSURE))) + self.data.console_queue.put("CAP_PROP_CONVERT_RGB=" + str(self.stream.get(cv2.CAP_PROP_CONVERT_RGB))) + self.data.console_queue.put("CAP_PROP_RECTIFICATION=" + str(self.stream.get(cv2.CAP_PROP_RECTIFICATION))) + self.data.console_queue.put("CAP_PROP_ISO_SPEED=" + str(self.stream.get(cv2.CAP_PROP_ISO_SPEED))) + self.data.console_queue.put("CAP_PROP_BUFFERSIZE=" + str(self.stream.get(cv2.CAP_PROP_BUFFERSIZE))) + + if cameraOff: + self.stream.release() + self.stream = None + ''' + + def start(self, src = 0): # start the thread to read frames from the video stream + return self + ''' + following is unreachable + print("Starting camera thread") - Thread(target=self.update, args=()).start() - print("Camera thread started") + if self.stream is None: + self.stream = cv2.VideoCapture(src) + (self.grabbed, self.frame) = self.stream.read() + + #self.setVideoSize() + #self.setFPS() + + if self.stopped == True: + self.stopped = False + self.th = threading.Thread(target=self.update) + self.th.daemon = True + self.th.start() + print("Camera thread started") + #self.data.ui_queue.put("Action:updateCamera_on") + self.data.ui_queue1.put("Action", "updateCamera", "on") + else: + print("Camera already started") return self + ''' def update(self): # keep looping infinitely until the thread is stopped + return + ''' while True: + time.sleep(self.cameraSleep) + if not self.data.continuousCamera or time.time()-self.lastCameraRead < 20: + (self.grabbed, self.frame) = self.stream.read() + self.suspended = False + else: + if self.suspended == False: + #self.data.ui_queue.put("Action:updateCamera_off") + self.data.ui_queue1.put("Action", "updateCamera", "off") + self.suspended=True # if the thread indicator variable is set, stop the thread if self.stopped: + self.stream.release() + self.stream = None + #self.data.ui_queue.put("Action:updateCamera_off") + self.data.ui_queue1.put("Action", "updateCamera", "off") return - # otherwise, read the next frame from the stream - (self.grabbed, self.frame) = self.stream.read() + #if self.frame is not None: + #small = cv2.resize(self.frame, (256,192)) + #imgencode = cv2.imencode(".png",small )[1] + #stringData = base64.b64encode(imgencode).decode() + #self.data.cameraImage = stringData + #self.data.cameraImageUpdated = True + ''' def read(self): # return the frame most recently read - print("Reading camera frame") + #print("Reading camera frame") + return None + ''' + if self.suspended: + (self.grabbed, self.frame) = self.stream.read() + self.suspended = False + #self.data.ui_queue.put("Action:updateCamera_on") + self.data.ui_queue1.put("Action", "updateCamera", "on") + self.lastCameraRead = time.time() + + if self.stopped: + self.start() return self.frame + ''' def stop(self): # indicate that the thread should be stopped print("Stopping camera") self.stopped = True + + def status(self): + if self.stopped: + return("stopped") + if self.suspended: + return("suspended") + return("running") + + def changeSetting(self, key, value): + return + ''' + if key == 'fps' and value != self.fps: + self.fps = value + if self.stream is not None: + self.setFPS() + if key == 'videoSize' and value != self.videoSize: + self.videoSize = value + if self.stream is not None: + self.setVideoSize() + if key == 'cameraSleep' and value != self.cameraSleep: + if value<1: + print("changing sleep interval") + self.cameraSleep = value + if self.stream is not None: + self.stopped = True + self.stream.join() + self.start() + ''' + + def setFPS(self): + return + #self.stream.set(cv2.CAP_PROP_FPS, self.fps) + + def setVideoSize(self): + return + width = 640 + height = 480 + if self.videoSize == '1024x768': + width = 1024 + height = 768 + #self.stream.set(cv2.CAP_PROP_FRAME_HEIGHT, height) + #self.stream.set(cv2.CAP_PROP_FRAME_WIDTH, width) diff --git a/Background/scheduler.py b/Boards/__init__.py similarity index 100% rename from Background/scheduler.py rename to Boards/__init__.py diff --git a/Boards/boardManager.py b/Boards/boardManager.py new file mode 100644 index 00000000..38aea373 --- /dev/null +++ b/Boards/boardManager.py @@ -0,0 +1,293 @@ +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs +from Boards.boards import Board +import math +import base64 +import numpy as np +from scipy.spatial import ConvexHull, convex_hull_plot_2d + +class BoardManager(MakesmithInitFuncs): + ''' + This class implements the management of various boards (workpieces) that are tracked. + Each board is stored as a separate file containing both description, dimensions, makeup of board as well + as an array (1-inch resolution) of what parts of the board have been cut. + ''' + currentBoard = None + + def __init__(self): + # can't do much because data hasn't been initialized yet + pass + + def initializeNewBoard(self): + ''' + Create a new board and initialize it to the size of the bed. Default to 0.75 inches thick + :return: + ''' + self.currentBoard = Board() + bedWidth = round(float(self.data.config.getValue("Maslow Settings", "bedWidth"))/25.4, 2) + bedHeight = round(float(self.data.config.getValue("Maslow Settings", "bedHeight"))/25.4, 2) + + self.currentBoard.updateBoardInfo("-", "-", bedHeight, bedWidth, 0.75, 0, 0, "inches") + # this creates the necessary compressed data files to avoid None errors. + self.currentBoard.compressCutData() + + def getCurrentBoard(self): + ''' + Returns current board + :return: + ''' + return self.currentBoard + + def getCurrentBoardFilename(self): + ''' + Returns current board filename + :return: + ''' + return self.currentBoard.boardFilename + + def editBoard(self, result): + ''' + Updates the board information with data from the form. + :param result: + :return: + ''' + try: + if self.currentBoard.updateBoardInfo(result["boardID"], result["material"], result["height"], + result["width"], result["thickness"], result["centerX"], + result["centerY"], result["units"]): + # send update to the UI clients + self.data.ui_queue1.put("Action", "boardUpdate", "") + return True + else: + return False + except Exception as e: + self.data.console_queue.put(str(e)) + return False + + def saveBoard(self, fileName, directory): + ''' + Saves the board data. File format is one line of board data in json format and one line of cut data in + compressed and base64 encoded format. + :param fileName: filename to use + :param directory: directory to save file + :return: + ''' + if fileName is "": # Blank the g-code if we're loading "nothing" + return False + if directory is "": + return False + try: + fileToWrite = directory + "/" + fileName + file = open(fileToWrite, "w+") + print(fileToWrite) + self.currentBoard.setFilename(fileName) + boardData = self.currentBoard.getBoardInfoJSON() + file.write(boardData+'\n') + boardCutData = self.currentBoard.getCompressedCutData() + boardCutData = base64.b64encode(boardCutData) + boardCutData = boardCutData.decode('utf-8') + file.write(boardCutData) + file.write('\n') + print("Closing File") + file.close() + except Exception as e: + self.data.console_queue.put(str(e)) + self.data.console_queue.put("Board Save File Error") + self.data.ui_queue1.put("Alert", "Alert", "Cannot save board.") + return False + return True + + def loadBoard(self, fileName): + ''' + Load the board data. File format is one line of board data in json format and one line of cut data in + compressed and base64 encoded format. + :param fileName: filename to load + :param directory: directory to load file from + :return: + ''' + if fileName is "": # Blank the g-code if we're loading "nothing" + return False + try: + file = open(fileName, "r") + print(fileName) + lines = file.readlines() + self.currentBoard.updateBoardInfoJSON(lines[0]) + # make sure got at least 2 lines... + if len(lines) > 1: + loadedCutData = base64.b64decode(lines[1].encode('utf-8')) + self.currentBoard.updateCompressedCutData(loadedCutData) + print("Closing File") + file.close() + self.data.ui_queue1.put("Action", "boardUpdate", "") + except Exception as e: + self.data.console_queue.put(str(e)) + self.data.console_queue.put("Board Open File Error") + self.data.ui_queue1.put("Alert", "Alert", "Cannot open board.") + return False + return True + + def processGCode(self): + ''' + Using the gcode in memory, mark the areas in the array that the gcode passes through at a height less than 0. + :return: + ''' + boardWidth = self.currentBoard.width + boardHeight = self.currentBoard.height + boardLeftX = self.currentBoard.centerX - boardWidth/2 + boardRightX = self.currentBoard.centerX + boardWidth / 2 + boardTopY = self.currentBoard.centerY + boardWidth/2 + boardBottomY = self.currentBoard.centerY - boardWidth / 2 + + # calculate the extents of the array and its offset. + pointsX = math.ceil(boardWidth) + pointsY = math.ceil(boardHeight) + offsetX = pointsX / 2 - self.currentBoard.centerX + offsetY = pointsY / 2 - self.currentBoard.centerY + + if self.data.units == "MM": + scale = 1/25.4 + else: + scale = 1 + homeX = self.data.gcodeShift[0]*scale + homeY = self.data.gcodeShift[1]*scale + + + # initialize an array + cutPoints = [False for i in range( pointsX * pointsY )] + + # process gcode + for line in self.data.gcodeFile.line3D: + if line.type == "circle": + if line.points[0][0] + homeX >= boardLeftX and line.points[0][0] + homeX <= boardRightX and line.points[0][1] + homeY >= boardBottomY and line.points[0][1] + homeY <= boardTopY and line.points[0][2] < 0: + pointx = self.constrain(round(line.points[0][0] + offsetX + homeX), 0, pointsX) + pointy = self.constrain(round(line.points[0][1] + offsetY + homeY), 0, pointsY) + cutPoints[pointx + pointy * pointsX] = True + #cutPoints[int(line.points[0][0] + offsetX) + int(line.points[0][1] + offsetY) * pointsX] = True + else: + for x in range(len(line.points)): + if x != len(line.points)-1: + x0 = line.points[x][0]+homeX + y0 = line.points[x][1]+homeY + z0 = line.points[x][2] + + x1 = line.points[x+1][0]+homeX + y1 = line.points[x+1][1]+homeY + z1 = line.points[x+1][2] + + lineLength = math.sqrt( (x0-x1) ** 2 + (y0-y1) ** 2 + (z0-z1) ** 2) + if lineLength > 0.25: + for l in range(int(lineLength*4)+1): + xa = x0 + (x1 - x0) / (lineLength * 4) * l + ya = y0 + (y1 - y0) / (lineLength * 4) * l + za = z0 + (z1 - z0) / (lineLength * 4) * l + if za < 0: + if xa >= boardLeftX and xa <= boardRightX and ya >= boardBottomY and ya <= boardTopY: + pointx = self.constrain(round(xa + offsetX), 0, pointsX) + pointy = self.constrain(round(ya + offsetY), 0, pointsY) + cutPoints[pointx + pointy * pointsX] = True + #cutPoints[round(xa + offsetX) + round(ya + offsetY) * pointsX] = True + + else: + if line.points[x][2] < 0: + if line.points[x][0] + homeX >= boardLeftX and line.points[x][0] + homeX <= boardRightX and line.points[x][1] + homeY >= boardBottomY and line.points[x][1] + homeX <= boardTopY: + pointx = self.constrain(round(line.points[x][0] + offsetX + homeX), 0, pointsX) + pointy = self.constrain(round(line.points[x][1] + offsetY + homeY), 0, pointsY) + cutPoints[pointx + pointy * pointsX] = True + if line.points[x+1][2] < 0: + if line.points[x+1][0] + homeX >= boardLeftX and line.points[x+1][0] + homeX <= boardRightX and line.points[x+1][1] + homeY >= boardBottomY and line.points[x+1][1] + homeY <= boardTopY: + pointx = self.constrain(round(line.points[x+1][0] + offsetX + homeX), 0, pointsX) + pointy = self.constrain(round(line.points[x+1][1] + offsetY + homeY), 0, pointsY) + cutPoints[pointx + pointy * pointsX] = True + + + else: + if line.points[x][2] < 0: + if line.points[x][0] + homeX >= boardLeftX and line.points[x][0] + homeX <= boardRightX and line.points[x][1] + homeY >= boardBottomY and line.points[x][1] + homeY <= boardTopY: + pointx = self.constrain(round(line.points[x][0] + offsetX + homeX), 0, pointsX) + pointy = self.constrain(round(line.points[x][1] + offsetY + homeY), 0, pointsY) + cutPoints[pointx + pointy * pointsX] = True + + # send this array to the current board for updating + self.currentBoard.updateCutPoints(cutPoints) + # update the UI clients. + self.data.ui_queue1.put("Action", "boardUpdate", "") + return True + + def clearBoard(self): + ''' + Clear the current board cut data + :return: + ''' + self.currentBoard.clearCutPoints() + # update the UI clients. + self.data.ui_queue1.put("Action", "boardUpdate", "") + return True + + def constrain(self, value, lower, upper): + ''' + Helper routine to constrain values + :param value: value to be constrained + :param lower: lower limit + :param upper: upper limit + :return: + ''' + if value < lower: + return lower + if value > upper-1: + return upper-1 + return value + + def trimBoard(self, result): + ''' + Processes message from form to trim the board cut data. + :param result: + :return: + ''' + trimTop = round(float(result["trimTop"]), 3) + trimBottom = round(float(result["trimBottom"]), 3) + trimLeft = round(float(result["trimLeft"]), 3) + trimRight = round(float(result["trimRight"]), 3) + units = result["units"] + retval = self.currentBoard.trimBoard(trimTop, trimBottom, trimLeft, trimRight, units) + self.data.ui_queue1.put("Action", "boardUpdate", "") + return retval + + ''' + old stuff not used anymore.. keeping it around for a bit + # Todo: delete when done with + def processGCode(self): + #points = np.random.rand(30,2) + points = self.data.gcodeFile.getLinePoints() + #try: + index = 0 + + for line in points: + #print(line) + point = np.zeros(2) + #print(point) + point[0] = line[0] + point[1] = line[1] + #print(point) + if index == 0: + npoints = [point] + else: + npoints = np.append(npoints, [point], axis=0) + index += 1 + #print(npoints) + hull = ConvexHull(npoints) + print("here0") + cutPoints = [] + for vertex in hull.vertices: + cutPoints.append([hull.points[vertex][0],hull.points[vertex][1],0]) + print("here1") + self.currentBoard.updateCutPoints(cutPoints) + self.data.ui_queue1.put("Action", "boardUpdate", "") + #except Exception as e: + # self.data.console_queue.put(str(e)) + # self.data.console_queue.put("Gcode Processing Error") + # self.data.ui_queue1.put("Alert", "Alert", "Cannot process gcode.") + # return False + + return True + ''' + + diff --git a/Boards/boards.py b/Boards/boards.py new file mode 100644 index 00000000..a15a73fc --- /dev/null +++ b/Boards/boards.py @@ -0,0 +1,237 @@ +import json +import gzip +import io +import math + + +class Board(): + ''' + Class is the generalization of a board that tracks board information including areas that have been cut. Resolution + is 1-inch squares. + ''' + def __init__(self): + # can't do much because data hasn't been initialized yet + pass + + width = 0 + height = 0 + thickness = 0 + centerX = 0 + centerY = 0 + + boardID = "Undefined" + material = "Undefined" + boardFilename = "" + + ### + # old, not sure is used + # todo: delete boardPoints and cutPoints2 if not used + boardPoints = [] + cutPoints2 = [] + ### + + cutPoints = [] + pointsPerInch = 1 + compressedCutData = "" + + def updateBoardInfo(self, boardID, material, height, width, thickness, centerX, centerY, units): + ''' + Updates the cut data + :param boardID: Name give to board, as entered by user + :param material: Type of material of board, as entered by user + :param height: height of board, stored in inches but entered as defined by units + :param width: width of board, stored in inches but entered as defined by units + :param thickness: thickness of board, stored in inches but entered as defined by units + :param centerX: X-coordinate of center of board, stored in inches but entered as defined by units + :param centerY: Y-coordinate of center of board, stored in inches but entered as defined by units + :param units: units the measurements are provided in. + :return: + ''' + + try: + scale = 1 + if units == "mm": + scale = 25.4 + self.width = round(float(width)/scale, 2) + self.height = round(float(height)/scale, 2) + self.thickness = round(float(thickness)/scale, 2) + self.centerX = round(float(centerX)/scale, 2) + self.centerY = round(float(centerY)/scale, 2) + self.boardID = boardID + self.material = material + return True + except Exception as e: + print(e) + return False + + def updateCutPoints(self, data): + ''' + Using array received from board manager, updates cut data and recompresses. + :param data: + :return: + ''' + if len(self.cutPoints) == 0: + #if cutdata isn't an array yet, then use the cut data (i.e., no existing data) + self.cutPoints = data + else: + # existing cut data exists, so add this data + for x in range(len(self.cutPoints)): + # if the data in data is cut (True) then make the data in cutPoints true as well.. i.e., performs + # an OR operation + if data[x]: + self.cutPoints[x] = True + # call to compress the cut data. + self.compressCutData() + + def trimBoard(self, trimTop, trimBottom, trimLeft, trimRight, units): + ''' + Trims portion of the board and updates cutdata + :param trimTop: Amount to trim off top, units as defined in units + :param trimBottom: Amount to trim off bottom, units as defined in units + :param trimLeft: Amount to trim off left, units as defined in units + :param trimRight: Amount to trim off left, units as defined in units + :param units: units of trim measurements + :return: + ''' + # adjust for correct units (i.e., convert to inches and round to 2 decimal points) + scale = 1 + if units == "mm": + scale = 25.4 + trimTop = round(float(trimTop)/scale, 2) + trimBottom = round(float(trimBottom) / scale, 2) + trimLeft = round(float(trimLeft) / scale, 2) + trimRight = round(float(trimRight) / scale, 2) + + # determine the new array extents + aPointsX = math.ceil(self.width) + aPointsY = math.ceil(self.height) + bPointsX = math.ceil(self.width - trimLeft - trimRight) + bPointsY = math.ceil(self.height - trimTop - trimBottom) + + # create a new cut array + bCutPoints = [False for i in range( bPointsX * bPointsY )] + + ''' + print(aPointsX) + print(aPointsY) + print(bPointsX) + print(bPointsY) + print(trimTop) + print(trimBottom) + print(trimLeft) + print(trimRight) + ''' + # if cutPoints are found... + if (len(self.cutPoints)!=0): + # iterate through new array and translate to old cut array points and assign matrix values. + for x in range(bPointsX): + for y in range(bPointsY): + ax = x + int(trimLeft) + ay = y + int(trimBottom) + ib = x+y*bPointsX + ia = ax+ay*aPointsX + #print(str(ib) +", "+ str(ia)) + bCutPoints[ib] = self.cutPoints[ia] + # assign cutPoints to new array + self.cutPoints = bCutPoints + # update dimensions + self.height = self.height - trimTop - trimBottom + self.width = self.width - trimLeft - trimRight + # compress data + self.compressCutData() + return True + + def setFilename(self, data): + ''' + Sets the filename of the board + :param data: + :return: + ''' + self.boardFilename = data + + def getPoints(self): + ''' + Don't think this is used. + todo: remove if not needed + :return: + ''' + return self.boardPoints + + def getCutPoints(self): + ''' + Returns uncompressed cut point data + :return: + ''' + return self.cutPoints + + def getCompressedCutData(self): + ''' + returns compressed cut point data + :return: + ''' + return self.compressedCutData + + def getBoardInfoJSON(self): + ''' + Returns board information formatted as a json + :return: + ''' + tstr = json.dumps({"width": self.width, "height": self.height, "thickness": self.thickness, "centerX": self.centerX, "centerY": self.centerY, "boardID":self.boardID, "material":self.material, "fileName":self.boardFilename}) + return tstr + + def updateBoardInfoJSON(self, data): + ''' + updates board data from a json + :param data: + :return: + ''' + boardData = json.loads(data) + self.width = boardData["width"] + self.height = boardData["height"] + self.thickness = boardData["thickness"] + self.centerX = boardData["centerX"] + self.centerY = boardData["centerY"] + self.boardID = boardData["boardID"] + self.material = boardData["material"] + self.boardFilename = boardData["fileName"] + + def compressCutData(self): + ''' + Compresses cut data using gzip + :return: + ''' + tstr = json.dumps(self.cutPoints) + out = io.BytesIO() + with gzip.GzipFile(fileobj=out, mode="w") as f: + f.write(tstr.encode()) + self.compressedCutData = out.getvalue() + + def getUnCompressedCutDataJSON(self): + ''' + returns uncompressed cut data in json format. + Not sure is used anymore + todo: delete if not needed + :return: + ''' + tstr = json.dumps(self.cutPoints) + return tstr + + def updateCompressedCutData(self, data): + ''' + Updates the compressed cut data using data, uncompresses it and assigns it to cutPoints. Used in loading + a board + :param data: + :return: + ''' + self.compressedCutData = data + mem = io.BytesIO(data) + f = gzip.GzipFile(fileobj=mem, mode="rb") + self.cutPoints = json.loads(f.read().decode()) + + def clearCutPoints(self): + ''' + clears the cut points and compressed cut data + :return: + ''' + self.cutPoints = [] + self.compressedCutData = None \ No newline at end of file diff --git a/Connection/nonVisibleWidgets.py b/Connection/nonVisibleWidgets.py index b5b09bd4..95cbdc98 100644 --- a/Connection/nonVisibleWidgets.py +++ b/Connection/nonVisibleWidgets.py @@ -1,12 +1,24 @@ +import sys +import distro +import os +import platform from DataStructures.makesmithInitFuncs import MakesmithInitFuncs from Connection.serialPort import SerialPort from File.gcodeFile import GCodeFile from File.importFile import ImportFile from Actions.actions import Actions from Actions.triangularCalibration import TriangularCalibration -from Actions.opticalCalibration import OpticalCalibration +from Actions.holeyCalibration import HoleyCalibration +from Actions.HoleySimulationKinematics import Kinematics as HoleyKinematics +from Actions.gpioActions import GPIOActions from Background.messageProcessor import MessageProcessor - +from Background.WebMCPProcessor import WebMCPProcessor +from Background.WebMCPProcessor import ConsoleProcessor +from Background.webcamVideoStream import WebcamVideoStream +from Boards.boardManager import BoardManager +from ReleaseManager.releaseManager import ReleaseManager +from HelpManager.helpManager import HelpManager +#from GCodeOptimizer.gcodeOptimizer import GCodeOptimizer class NonVisibleWidgets(MakesmithInitFuncs): """ @@ -21,8 +33,17 @@ class NonVisibleWidgets(MakesmithInitFuncs): importFile = ImportFile() actions = Actions() triangularCalibration = TriangularCalibration() - opticalCalibration = OpticalCalibration() + holeyCalibration = HoleyCalibration() + holeyKinematics = HoleyKinematics() messageProcessor = MessageProcessor() + mcpProcessor = WebMCPProcessor() + consoleProcessor = ConsoleProcessor() + camera = WebcamVideoStream() + gpioActions = GPIOActions() + boardManager = BoardManager() + releaseManager = ReleaseManager() + helpManager = HelpManager() + #gcodeOptimizer = GCodeOptimizer() def setUpData(self, data): """ @@ -43,12 +64,75 @@ def setUpData(self, data): data.importFile = self.importFile data.actions = self.actions data.triangularCalibration = self.triangularCalibration - data.opticalCalibration = self.opticalCalibration + data.holeyCalibration = self.holeyCalibration + data.holeyKinematics = self.holeyKinematics data.messageProcessor = self.messageProcessor + data.mcpProcessor = self.mcpProcessor + data.consoleProcessor = self.consoleProcessor + data.camera = self.camera + data.gpioActions = self.gpioActions + data.boardManager = self.boardManager + data.releaseManager = self.releaseManager + data.helpManager = self.helpManager + #data.gcodeOptimizer = self.gcodeOptimizer + + if hasattr(sys, '_MEIPASS'): + data.platform = "PYINSTALLER" + data.platformHome = sys._MEIPASS + + data.pyInstallPlatform = platform.system().lower() + + if data.pyInstallPlatform == "windows": + if platform.machine().endswith('64'): + data.pyInstallPlatform = "win64" + if platform.machine().endswith('32'): + data.pyInstallPlatform = "win32" + + if data.pyInstallPlatform == "linux": + _platform = distro.linux_distribution()[0].lower() + print("##") + print(_platform) + print("##") + if _platform.find("raspbian") != -1: + data.pyInstallPlatform = 'rpi' + print("----") + print(data.pyInstallPlatform) + + + if getattr(sys, 'frozen', False): + if hasattr(sys, '_MEIPASS'): + if sys._MEIPASS.find("_MEI") == -1: + data.pyInstallType = "singledirectory" + else: + data.pyInstallType = "singlefile" + else: + data.pyInstallType = "singledirectory" + + print(data.pyInstallType) + print("----") + self.serialPort.setUpData(data) self.gcodeFile.setUpData(data) self.importFile.setUpData(data) self.actions.setUpData(data) self.triangularCalibration.setUpData(data) - self.opticalCalibration.setUpData(data) + self.holeyCalibration.setUpData(data) + self.holeyKinematics.setUpData(data) self.messageProcessor.setUpData(data) + self.mcpProcessor.setUpData(data) + self.consoleProcessor.setUpData(data) + self.camera.setUpData(data) + self.camera.getSettings() + self.gpioActions.setUpData(data) + self.gpioActions.setup() + self.boardManager.setUpData(data) + self.boardManager.initializeNewBoard() + self.releaseManager.setUpData(data) + self.helpManager.setUpData(data) + #self.gcodeOptimizer.setUpData(data) + + #set up kinematics with current settings + self.holeyKinematics.initializeSettings() + #self.camera.start() + + diff --git a/Connection/serialPort.py b/Connection/serialPort.py index d4473f59..17471475 100644 --- a/Connection/serialPort.py +++ b/Connection/serialPort.py @@ -7,7 +7,7 @@ import threading import schedule import time - +import json class SerialPort(MakesmithInitFuncs): """ @@ -17,6 +17,7 @@ class SerialPort(MakesmithInitFuncs): The actual connection is run in a separate thread by an instance of a SerialPortThread object. """ + serialPortRequest = "" # COMports = ListProperty(("Available Ports:", "None")) @@ -33,8 +34,7 @@ def setPort(self, port): Defines which port the machine is attached to """ - print("update ports") - print(port) + self.data.console_queue.put(port) self.data.comport = port def connect(self, *args): @@ -57,14 +57,29 @@ def connect(self, *args): def openConnection(self, *args): # This function opens the thread which handles the input from the serial port - # It only needs to be run once, it is run by connecting to the machine - # print("Attempting to open connection to controller") if not self.data.connectionStatus: - # self.data.message_queue is the queue which handles passing CAN messages between threads - # print "serialport.self.app.logger="+str(self.app.logger) + #self.data.ui_queue.put( + # "Action: connectionStatus:_" + json.dumps({'status': 'disconnected', 'port': 'none'}) + #) # the "_" facilitates the parse + self.data.ui_queue1.put("Action", "connectionStatus", + {'status': 'disconnected', 'port': 'none', 'fakeServoStatus': self.data.fakeServoStatus}) x = SerialPortThread() x.data = self.data self.th = threading.Thread(target=x.getmessage) self.th.daemon = True self.th.start() + else: + self.data.ui_queue1.put("Action", "connectionStatus", + {'status': 'connected', 'port': self.data.comport, 'fakeServoStatus': self.data.fakeServoStatus}) + #self.data.ui_queue.put( + # "Action: connectionStatus:_" + json.dumps({'status': 'connected', 'port': self.data.comport}) + #) # the "_" facilitates the parse + + def closeConnection(self): + self.serialPortRequest = "requestToClose" + + def getConnectionStatus(self): + return self.serialPortRequest + + diff --git a/Connection/serialPortThread.py b/Connection/serialPortThread.py index e0ed2756..441fc588 100644 --- a/Connection/serialPortThread.py +++ b/Connection/serialPortThread.py @@ -3,6 +3,8 @@ import serial import time from collections import deque +import json +import re class SerialPortThread(MakesmithInitFuncs): @@ -24,111 +26,234 @@ class SerialPortThread(MakesmithInitFuncs): bufferSize = 126 # The total size of the arduino buffer bufferSpace = bufferSize # The amount of space currently available in the buffer lengthOfLastLineStack = deque() - + weAreBufferingLines = 0 # Minimum time between lines sent to allow Arduino to cope # could be smaller (0.02) however larger number doesn't seem to impact performance MINTimePerLine = 0.05 - def _write(self, message, isQuickCommand=False): - # message = message + 'L' + str(len(message) + 1 + 2 + len(str(len(message))) ) + serialInstance = None + def _write(self, message, isQuickCommand=False): + ''' + Sends messages to controller. No change from what I can tell from ground control + :param message: + :param isQuickCommand: + :return: + ''' taken = time.time() - self.lastWriteTime if taken < self.MINTimePerLine: # wait between sends - # self.data.logger.writeToLog("Sleeping: " + str( taken ) + "\n") time.sleep(self.MINTimePerLine) # could use (taken - MINTimePerLine) message = message + "\n" - # message = message.encode() - print("Sending: " + str(message)) - - self.bufferSpace = self.bufferSpace - len( - message - ) # shrink the available buffer space by the length of the line - - self.machineIsReadyForData = False - - # if this is a quick message sent as soon as the button is pressed (like stop) then put it on the right side of the queue - # because it is the first message sent, otherwise put it at the end (left) because it is the last message sent - if isQuickCommand: - if message[0] == "!": - # if we've just sent a stop command, the buffer is now empty on the arduino side - self.lengthOfLastLineStack.clear() - self.bufferSpace = self.bufferSize - len(message) - self.lengthOfLastLineStack.append(len(message)) + + if len(message) > 1: + self.data.console_queue.put("Sending: " + str(message).rstrip('\n')) + + self.bufferSpace = self.bufferSpace - len( + message + ) # shrink the available buffer space by the length of the line + + self.machineIsReadyForData = False + + # if this is a quick message sent as soon as the button is pressed (like stop) then put it on the right side of the queue + # because it is the first message sent, otherwise put it at the end (left) because it is the last message sent + if isQuickCommand: + if message[0] == "!": + # if we've just sent a stop command, the buffer is now empty on the arduino side + self.lengthOfLastLineStack.clear() + self.bufferSpace = self.bufferSize - len(message) + self.lengthOfLastLineStack.append(len(message)) + else: + self.lengthOfLastLineStack.append(len(message)) else: - self.lengthOfLastLineStack.append(len(message)) + self.lengthOfLastLineStack.appendleft(len(message)) + + ''' + Monitor gcode for positioning mode change requests + ''' + positioningMode = None + findG90 = message.rfind("G90") + findG91 = message.rfind("G91") + + if findG90 != -1 and findG91 != -1: + if findG90 > findG91: + positioningMode = 0 + else: + positioningMode = 1 + else: + if findG90 != -1: + positioningMode = 0 + if findG91 != -1: + positioningMode = 1 + + message = message.encode() + + ''' + try sending message + ''' + try: + self.serialInstance.write(message) + # Update positioning mode after message has been sent. + # In 'try' block to maintain state integrity if message send fails. + if (positioningMode is not None): + self.data.positioningMode = positioningMode + #print("Set positioning mode: " + str(positioningMode)) + self.data.logger.writeToLog("Sent: " + str(message.decode())) + except: + self.data.console_queue.put("write issue") + self.data.logger.writeToLog("Send FAILED: " + str(message.decode())) + + self.lastWriteTime = time.time() else: - self.lengthOfLastLineStack.appendleft(len(message)) - - message = message.encode() - try: - self.serialInstance.write(message) - self.data.logger.writeToLog("Sent: " + str(message)) - except: - print("write issue") - self.data.logger.writeToLog("Send FAILED: " + str(message)) - - self.lastWriteTime = time.time() + self.data.console_queue.put("Skipping: " + str(message).rstrip('\n')) def _getFirmwareVersion(self): + ''' + Send command to have controller report details + :return: + ''' self.data.gcode_queue.put("B05 ") def _setupMachineUnits(self): + ''' + Send command to put controller in correct units state. + :return: + ''' if self.data.units == "INCHES": self.data.gcode_queue.put("G20 ") else: self.data.gcode_queue.put("G21 ") + def _requestSettingsUpdate(self): + ''' + Send command to have controller report settings + :return: + ''' + self.data.gcode_queue.put("$$") + def sendNextLine(self): """ Sends the next line of gcode to the machine """ if self.data.gcodeIndex < len(self.data.gcode): - if self.data.uploadFlag: - self._write(self.data.gcode[self.data.gcodeIndex]) + line = self.data.gcode[self.data.gcodeIndex] + # filter comments from line + filtersparsed = re.sub(r'\(([^)]*)\)', '', line) # replace mach3 style gcode comments with newline + line = re.sub(r';([^\n]*)?', '',filtersparsed) # replace standard ; initiated gcode comments with newline + # check if command is going to be issued that pauses the controller. + self.managePause(line) + self.manageToolChange(line) + if not line.isspace(): # if all spaces, don't send. likely a comment. + # put gcode home shift here.. only if in absolute mode (G90) + if self.data.positioningMode == 0: + line = self.data.gcodeFile.moveLine(line) + self._write(line) + # if there is a units change, then update the UI client so position messages are processed correctly. + if line.find("G20") != -1: + if self.data.units != "INCHES": + self.data.actions.updateSetting("toInches", 0, True) # value = doesn't matter + if line.find("G21") != -1: + if self.data.units != "MM": + self.data.actions.updateSetting("toMM", 0, True) # value = doesn't matter + # send a gcode update to UI client. + self.data.actions.sendGCodePositionUpdate(self.data.gcodeIndex) + # track current target Z-Axis position + z = re.search("Z(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", line) + if z: + self.data.currentZTarget = float(z.groups()[0]) + #self.data.currentZTargetUnits = self.data.units + + # increment gcode index + if self.data.gcodeIndex + 1 < len(self.data.gcode): + self.data.gcodeIndex = self.data.gcodeIndex + 1 + else: + self.data.uploadFlag = 0 + self.data.gcodeIndex = 0 + self.data.console_queue.put("Gcode Ended") + + def managePause(self, line): + if line.find("M0 ") != -1 or line.find("M00") != -1 or line.find("M1 ") != -1 or line.find("M01") != -1: + print("found M command for pause") + self.data.uploadFlag = -1 + self.data.pausedUnits = self.data.units + self.data.ui_queue1.put("Action", "setAsResume", "") + + def manageToolChange(self, line): + if line.find("M6 ") != -1 or line.find("M06") != -1: + # if this is a different tool, the controller will respond with a 'Tool Change:' and pause. + # if this is a the same tool as the controller is currently tracking, it will continue on. + # first, determine the tool being called for... + toolNumber = int(self.extractGcodeValue(line, 'T', 0)) + print(toolNumber) + print(self.data.currentTool) + # so, in the first case... + if toolNumber != self.data.currentTool: + # set uploadFlag to -1 to turn off sending more lines (after this one) + # -1 means it was set by an M command + print("found M command") + self.data.uploadFlag = -1 + self.data.currentTool = toolNumber + self.data.pausedUnits = self.data.units + ## new stuff + #self.data.quick_queue.put("~") + #self.data.ui_queue1.put("Action", "setAsResume", "") + ## end new stuff + + # now, the issue is that if the controller gets reset, then the tool number will revert to 0.. so + # on serial port connect/reconnect, reinitialize tool number to 0 + + # but in the second case, just continue on.. + + ## new stuff + #self.data.quick_queue.put("~") + #self.data.ui_queue1.put("Action", "setAsResume", "") + ## end new stuff + + def closeConnection(self): + ''' + Closes the serial connection and updates the status. Needed for firmware upgrades. + :return: + ''' + if self.serialInstance is not None: + self.serialInstance.close() + self.data.serialPort.serialPortRequest = "Closed" + print("connection closed at serialPortThread") + else: + print("serial Instance is none??") + return - # increment gcode index - if self.data.gcodeIndex + 1 < len(self.data.gcode): - self.data.gcodeIndex = self.data.gcodeIndex + 1 - else: - self.data.uploadFlag = 0 - self.data.gcodeIndex = 0 - print("Gcode Ended") def getmessage(self): - # opens a serial connection called self.serialInstance + ''' + Opens a serial connection called self.serialInstance + Processes all the messages from controller. + :return: + ''' # check for serial version being > 3 if float(serial.VERSION[0]) < 3: - self.data.ui_queue.put( - "Pyserial version 3.x is needed, version " + self.data.ui_queue1.put("Alert", "Incompability Detected", + "Pyserial version 3.x is needed, but version " + serial.VERSION + " is installed" ) - weAreBufferingLines = bool( - int(self.data.config.getValue("Maslow Settings", "bufferOn")) - ) + self.weAreBufferingLines = bool(int(self.data.config.getValue("Maslow Settings", "bufferOn")) ) try: - print("connecting") self.data.comport = self.data.config.getValue("Maslow Settings", "COMport") + connectMessage = "Trying to connect to controller on " +self.data.comport + self.data.console_queue.put(connectMessage) self.serialInstance = serial.Serial( self.data.comport, 57600, timeout=0.25 ) # self.data.comport is the com port which is opened except: - print(self.data.comport + " is unavailable or in use") - # self.data.ui_queue.put("\n" + self.data.comport + " is unavailable or in use") + #self.data.console_queue.put(self.data.comport + " is unavailable or in use") pass else: - print("\r\nConnected on port " + self.data.comport + "\r\n") - self.data.ui_queue.put( - "\r\nConnected on port " + self.data.comport + "\r\n" - ) - print("\r\nConnected on port " + self.data.comport + "\r\n") - gcode = "" - msg = "" - subReadyFlag = True + self.data.console_queue.put("\r\nConnected on port " + self.data.comport + "\r\n") + self.data.ui_queue1.put("Action", "connectionStatus", {'status': 'connected', 'port': self.data.comport, 'fakeServoStatus': self.data.fakeServoStatus}) + self.data.ui_queue1.put("TextMessage", "", "Connected on port " + self.data.comport) self.serialInstance.parity = ( serial.PARITY_ODD @@ -139,13 +264,12 @@ def getmessage(self): self.serialInstance.parity = serial.PARITY_NONE self.serialInstance.open() - # print "port open?:" - # print self.serialInstance.isOpen() self.lastMessageTime = time.time() self.data.connectionStatus = 1 - self._getFirmwareVersion() self._setupMachineUnits() + self._requestSettingsUpdate() + self.data.currentTool = 0 # This is necessary since the controller will have reset tool to zero. while True: @@ -153,28 +277,32 @@ def getmessage(self): # ------------------------------------------------------------------------------------- lineFromMachine = "" + # check to see if the serail port needs to be closed (for firmware upgrade) + if self.data.serialPort.serialPortRequest == "requestToClose": + print("processing request to close") + self.closeConnection() + # do not change status just yet... + return + try: if self.serialInstance.in_waiting > 0: + # the need for the .decode() at the end MIGHT be a python3 thing. ground control doesn't have + # it. lineFromMachine = self.serialInstance.readline().decode() - # lineFromMachine = lineFromMachine.encode('utf-8') self.lastMessageTime = time.time() self.data.message_queue.put(lineFromMachine) except: pass # Check if a line has been completed - if lineFromMachine == "ok\r\n" or ( - len(lineFromMachine) >= 6 and lineFromMachine[0:6] == "error:" - ): + if lineFromMachine == "ok\r\n" or (len(lineFromMachine) >= 6 and lineFromMachine[0:6] == "error:"): self.machineIsReadyForData = True - if ( - bool(self.lengthOfLastLineStack) is True - ): # if we've sent lines to the machine - self.bufferSpace = ( - self.bufferSpace + self.lengthOfLastLineStack.pop() - ) # free up that space in the buffer - - # Write to the machine if ready + if bool(self.lengthOfLastLineStack) is True: # if we've sent lines to the machine + # free up that space in the buffer + self.bufferSpace = (self.bufferSpace + self.lengthOfLastLineStack.pop()) + + + # Write to the machine if ready # ------------------------------------------------------------------------------------- # send any emergency instructions to the machine if there are any @@ -183,46 +311,101 @@ def getmessage(self): self._write(command, True) # send regular instructions to the machine if there are any - if self.bufferSpace == self.bufferSize and self.machineIsReadyForData: + #print("bSpace="+str(self.bufferSpace)+", bSize="+str(self.bufferSize)+", ready="+str(self.machineIsReadyForData)) + if self.bufferSpace == self.bufferSize: if self.data.gcode_queue.empty() != True: - command = self.data.gcode_queue.get_nowait() + " " - self._write(command) - - # Send the next line of gcode to the machine if we're running a program. Will send lines to buffer if there is space - # and the feature is turned on - if weAreBufferingLines: - try: - if self.bufferSpace > len( - self.data.gcode[self.data.gcodeIndex] - ): # if there is space in the buffer keep sending lines + if self.machineIsReadyForData: + command = self.data.gcode_queue.get_nowait()# + " " + # filter out comments + # replace mach3 style gcode comments with newline + filtersparsed = re.sub(r'\(([^)]*)\)', '', command) + # replace standard ; initiated gcode comments with '' + command = re.sub(r';([^\n]*)?', '', filtersparsed) + # if there's something left.. + if len(command) != 0: + command = command + " " + self.manageToolChange(command) + self._write(command) + # if units have changed, update settings and notify UI clients to stay in sync + if command.find("G20") != -1: + if self.data.units != "INCHES": + self.data.actions.updateSetting("toInches", 0, True) # value = doesn't matter + if command.find("G21") != -1: + if self.data.units != "MM": + self.data.actions.updateSetting("toMM", 0, True) # value = doesn't matter + # send updated gcode position to UI clients + self.data.actions.sendGCodePositionUpdate(self.data.gcodeIndex, recalculate=True) + # Send the next line of gcode to the machine if we're running a program and uploadFlag is enabled. Will + # send lines to buffer if there is space and the feature is turned on + # Also, don't send if there's still data in gcode_queue. + if self.data.uploadFlag == 1 and len(self.data.gcode) > 0 and self.data.gcode_queue.empty(): + if self.weAreBufferingLines: + try: + # todo: clean this up because the line gets filtered twice.. once to make sure its not too + # long, and the second in the sendNextLine command.. bit redundant. + line = self.data.gcode[self.data.gcodeIndex] + # replace mach3 style gcode comments with newline + filtersparsed = re.sub(r'\(([^)]*)\)', '', line) + # replace standard ; initiated gcode comments with newline + line = re.sub(r';([^\n]*)?', '', filtersparsed) + # if there is space in the buffer send line + if self.bufferSpace > len(line): + self.sendNextLine() + except IndexError: + self.data.console_queue.put("index error when reading gcode") + # we don't want the whole serial thread to close if the gcode can't be sent because of an + # index error (file deleted...etc) + else: + if (self.bufferSpace == self.bufferSize and self.machineIsReadyForData ): + # if the receive buffer is empty and the machine has acked the last line complete... self.sendNextLine() - except IndexError: - print( - "index error when reading gcode" - ) # we don't want the whole serial thread to close if the gcode can't be sent because of an index error (file deleted...etc) - else: - if ( - self.bufferSpace == self.bufferSize - and self.machineIsReadyForData - ): # if the receive buffer is empty and the machine has acked the last line complete - self.sendNextLine() - # Check for serial connection loss + # Check for serial connection loss # ------------------------------------------------------------------------------------- - if time.time() - self.lastMessageTime > 2: - print("Connection Timed Out") - self.data.ui_queue.put("Connection Timed Out\n") - if self.data.uploadFlag: - self.data.ui_queue.put( - "Message: USB connection lost. This has likely caused the machine to loose it's calibration, which can cause erratic behavior. It is recommended to stop the program, remove the sled, and perform the chain calibration process. Press Continue to override and proceed with the cut." - ) + if time.time() - self.lastMessageTime > 5: + self.data.console_queue.put("Connection Timed Out") + if self.data.uploadFlag > 0: + self.data.ui_queue1.put("Alert", "Connection Lost", + "Message: USB connection lost. This has likely caused the machine to loose it's calibration, which can cause erratic behavior. It is recommended to stop the program, remove the sled, and perform the chain calibration process. Press Continue to override and proceed with the cut.") else: - self.data.ui_queue.put( - "It is possible that the serial port selected is not the one used by the Maslow's Arduino,\nor that the firmware is not loaded on the Arduino." - ) + self.data.ui_queue1.put("SendAlarm", "Alarm: Connection Failed or Invalid Firmware", "") self.data.connectionStatus = 0 self.serialInstance.close() return - # Sleep between passes to save CPU - time.sleep(0.001) + if self.data.requestSerialClose: + # close down the serial port. + self.data.requestSerialClose = False + self.data.connectionStatus = 0 + self.serialInstance.close() + + time.sleep(0.01) + + def extractGcodeValue(self, readString, target, defaultReturn): + # Reads a string and returns the value of number following the target character. + # if no number is found, defaultReturn is returned + + begin = readString.find(target) + end = self.findEndOfNumber(readString, begin + 1) + numberAsString = readString[begin + 1: end] + try: + numberAsFloat = float(numberAsString) + except: + return defaultReturn + + if begin == -1: + return defaultReturn + else: + return numberAsFloat + + def findEndOfNumber(self, textString, index): + # Return the index of the last digit of the number beginning at the index passed in + + i = index + while i < len(textString): + if textString[i].isdigit() or textString[i] == '.': + i = i + 1 + else: + return i + return i + diff --git a/DataStructures/data.py b/DataStructures/data.py index 24d88134..c678f4ce 100644 --- a/DataStructures/data.py +++ b/DataStructures/data.py @@ -1,6 +1,7 @@ from time import time from DataStructures.logger import Logger from DataStructures.loggingQueue import LoggingQueue +from DataStructures.uiQueue import UIQueue from config.config import Config import queue @@ -22,11 +23,41 @@ class Data: # Gcodes contains all of the lines of gcode in the opened file clients = [] gcode = [] - version = "1.23" + gcodeFileUnits = "INCHES" + sentCustomGCode = "" + compressedGCode = None + compressedGCode3D = None + + version = "1.27" + stockFirmwareVersion = None + customFirmwareVersion = None + holeyFirmwareVersion = None + controllerFirmwareVersion = 0 + ''' + interpreter version + if using a compiler newer than 3.5, use the newer string format methods without %'s + ''' + pythonVersion35 = False + + ''' + Version Updater + ''' + lastChecked = -1 + pyInstallCurrentVersion = 0.9335 + pyInstallUpdateAvailable = False + pyInstallUpdateBrowserUrl = "" + pyInstallUpdateVersion = 0 + pyInstallPlatform = "rpi" + pyInstallType = "singlefile" + pyInstallInstalledPath = "" + + # all of the available COM ports comPorts = [] # This defines which COM port is used comport = "" + # stores value to indicate whether or not fake_servo is enabled + fakeServoStatus = False # The index of the next unread line of Gcode gcodeIndex = 0 # Index of changes in z @@ -36,12 +67,20 @@ class Data: # holds the address of the g-code file so that the gcode can be refreshed gcodeFile = "" importFile = "" + # holds the current gcode x,y,z position + currentGcodePost = [0.0, 0.0, 0.0] # the current position of the cutting head currentpos = [0.0, 0.0, 0.0] target = [0.0, 0.0, 0.0] units = "MM" + # Gcode positioning mode: + # 0 = G90 (Absolute) + # 1 = G91 (Relative) + positioningMode = 0 tolerance = 0.5 gcodeShift = [0.0, 0.0] # the amount that the gcode has been shifted + currentTool = 0 # current tool.. upon startup, 0 is the same value as what the controller would have. + currentZTarget = 0 # current target for Z-Axis move. Need to track so if user pauses, we can move back to that spot. message = "" # used to update the client logger = Logger() # the module which records the machines behavior to review later config = Config() @@ -57,21 +96,49 @@ class Data: # sets a flag if the gcode is being uploaded currently uploadFlag = 0 previousUploadStatus = 0 + manualZAxisAdjust = False # this is used to determine the first time the position is received from the machine firstTimePosFlag = 0 # report if the serial connection is open connectionStatus = 0 # is the calibration process currently underway 0 -> false calibrationInProcess = False - + inPIDVelocityTest = False + inPIDPositionTest = False + PIDVelocityTestVersion = 0 + PIDPositionTestVersion = 0 + GPIOButtonService = False + clidisplay = False # if you have a local RPI display + wiiPendantPresent = False # has user set wiimote as active? + wiiPendantConnected = False # is the wiimote BT connected? + sledMoving = False # for LED light status + zMoving = False + #gcode position flags for imported gcode to show outer bouding box + gcode_x_min = 2000 + gcode_x_max = -2000 + gcode_y_min = 1000 + gcode_y_max = -1000 + gcode_z_min = 20 + gcode_z_max = -20 + moveDistance = 10 # CHECK UNITS!! + """ Pointers to Objects """ serialPort = None # this is a pointer to the program serial port object + requestSerialClose = False # this is used to request the serialThread to gracefully close the port triangularCalibration = None # points to the triangular calibration object + holeyCalibration = None # points to the triangular calibration object opticalCalibration = None # points to the optical calibration object opticalCalibrationImage = None # stores the current image opticalCalibrationImageUpdated = False # stores whether its been updated or not + opticalCalibrationTestImage = None # stores the current image + opticalCalibrationTestImageUpdated = False # stores whether its been updated or not + cameraImage = None + cameraImageUpdated = False + continuousCamera = False + gpioActions = None + boardManager = None """ Colors @@ -91,11 +158,18 @@ class Data: zPopupUnits = None zStepSizeVal = 0.1 + """ Queues """ message_queue = LoggingQueue(logger) - ui_queue = queue.Queue() + ui_controller_queue = queue.Queue() + ui_queue1 = UIQueue() + alog_streamer_queue = queue.Queue(1000) # used for sending log to client screen.. limit to 1000 "items" + log_streamer_queue = queue.Queue(1000) # used for sending log to client screen.. limit to 1000 "items" + console_queue = queue.Queue() # used for printing to terminal + mcp_queue = queue.Queue () # used for sending messages to WebMCP(if enabled) + webMCPActive = False # start false until WebMCP connects gcode_queue = queue.Queue() quick_queue = queue.Queue() @@ -105,11 +179,57 @@ class Data: xval = 0.0 yval = 0.0 zval = 0.0 + xval_prev = -99990.0 + yval_prev = -99990.0 + zval_prev = -99990.0 + + leftError = 0.0 + rightError = 0.0 + leftError_prev = -99999.0 + rightError_prev = -99999.9 + + """ + Chain lengths as reported by controller + """ + leftChain = 1610 + rightChain = 1610 + + """ + Sled position computed from controller reported chain lengths + """ + computedX = 0 + computedY = 0 + + """ + Buffer size as reported by controller + """ + bufferSize = 127 + pausedzval = 0.0 + pausedPositioningMode = 0 + pausedUnits = "INCHES" + + """ + GCode Position Values + """ previousPosX = 0.0 previousPosY = 0.0 previousPosZ = 0.0 + """ + Board data + """ + currentBoard = None + + + shutdown = False + + hostAddress = "-" + platform = "RPI" + platformHome = "" + + + def __init__(self): """ diff --git a/DataStructures/logger.py b/DataStructures/logger.py index ef3fc43f..32e7445f 100644 --- a/DataStructures/logger.py +++ b/DataStructures/logger.py @@ -7,24 +7,76 @@ from DataStructures.makesmithInitFuncs import MakesmithInitFuncs import threading +import os +import time +import datetime +from pathlib import Path from app import app, socketio + class Logger(MakesmithInitFuncs): errorValues = [] recordingPositionalErrors = False clients = [] + logStartTime = 0 messageBuffer = "" amessageBuffer = "" - - # clear the old log file - with open("log.txt", "a") as logFile: - logFile.truncate() - - with open("alog.txt", "a") as logFile: - logFile.truncate() + idler = 0 + suspendLogging = False + lastALogWrite = 0 + lastLogWrite = 0 + loggingTimeout = -1 + + def __init__(self): + print("Initializing Logger") + self.home = str(Path.home()) + # clear the old log file + if not os.path.isdir(self.home + "/.WebControl"): + print("creating " + self.home + "/.WebControl directory") + os.mkdir(self.home + "/.WebControl") + print(self.home+"/.WebControl/"+"log.txt") + with open(self.home+"/.WebControl/"+"log.txt", "a") as logFile: + logFile.truncate() + + with open(self.home+"/.WebControl/"+"alog.txt", "a") as logFile: + logFile.truncate() + + self.logStartTime = time.time() + dateTime = datetime.datetime.fromtimestamp(self.logStartTime).strftime('%Y-%m-%d %H:%M:%S') + self.amessageBuffer = "+++++\n"+dateTime+"\n+++++\n".format(self.logStartTime) + self.messageBuffer = "+++++\n"+dateTime+"\n+++++\n".format(self.logStartTime) + self.idler = time.time() + self.lastALogWrite = self.idler + self.lastLogWrite = self.idler + + def resetIdler(self): + self.idler = time.time() + + def getLoggerState(self): + ''' + Returns the state of the logger + :return: + ''' + return self.suspendLogging + + def setLoggingTimeout(self, timeOut): + self.loggingTimeout = timeOut + + def addToMessageBuffer(self, message): + self.messageBuffer += message + if self.data.log_streamer_queue.full(): + self.data.log_streamer_queue.get_nowait() + self.data.log_streamer_queue.put_nowait(message) + + def addToaMessageBuffer(self, message): + self.amessageBuffer += message + + if self.data.alog_streamer_queue.full(): + self.data.alog_streamer_queue.get_nowait() + self.data.alog_streamer_queue.put_nowait(message) def writeToLog(self, message): @@ -36,47 +88,96 @@ def writeToLog(self, message): way slow """ + if self.loggingTimeout == -1: #get setting for suspend time + self.loggingTimeout = self.data.config.get("WebControl Settings", "loggingTimeout") + currentTime = time.time() + logTime = "{:0.2f}".format(currentTime-self.logStartTime) + dateTime = datetime.datetime.fromtimestamp(currentTime).strftime('%Y-%m-%d %H:%M:%S') + if self.loggingTimeout > 0 and self.data.uploadFlag <= 0 and currentTime-self.idler > self.loggingTimeout: + if not self.suspendLogging: + self.addToMessageBuffer(logTime + ": " + "Logging suspended due to user idle time > "+str(self.loggingTimeout)+" seconds\n") + self.suspendLogging = True + else: + if self.suspendLogging: + self.addToMessageBuffer(logTime + ": " + "Logging resumed due to user activity\n") + self.suspendLogging = False + if message[0] != "<" and message[0] != "[": try: - self.amessageBuffer = self.amessageBuffer + message - self.messageBuffer = self.messageBuffer + message + tmessage = message.rstrip('\r\n') + self.addToaMessageBuffer(logTime+": " + tmessage+"\n") + if not self.suspendLogging: + self.addToMessageBuffer(logTime+": " + tmessage+"\n") except: pass else: try: - self.messageBuffer = self.messageBuffer + message + if not self.suspendLogging: + tmessage = message.rstrip('\r\n') + self.addToMessageBuffer(logTime+": "+ tmessage+"\n") except: pass - if len(self.messageBuffer) > 0: - t = threading.Thread( - target=self.writeToFile, args=(self.messageBuffer, True, "write") - ) - t.daemon = True - t.start() - self.messageBuffer = "" - - if len(self.amessageBuffer) > 0: - t = threading.Thread( - target=self.writeToFile, args=(self.amessageBuffer, False, "write") - ) - t.daemon = True - t.start() - self.amessageBuffer = "" + if len(self.messageBuffer) > 500 or currentTime-self.lastLogWrite > 15: + if self.messageBuffer != "": #doing it this way will flush out the buffer when in idle state. + t = threading.Thread( + target=self.writeToFile, args=(self.messageBuffer, True, "write") + ) + t.daemon = True + t.start() + self.messageBuffer = "" + self.lastLogWrite = currentTime + + if len(self.amessageBuffer) > 500 or currentTime-self.lastALogWrite > 15: + if self.amessageBuffer != "": + t = threading.Thread( + target=self.writeToFile, args=(self.amessageBuffer, False, "write") + ) + t.daemon = True + t.start() + self.amessageBuffer = "" + self.lastALogWrite = currentTime def writeToFile(self, toWrite, log, *args): """ Write to the log file """ if log is True: - with open("log.txt", "a") as logFile: + with open(self.home+"/.WebControl/"+"log.txt", "a") as logFile: logFile.write(toWrite) else: - with open("alog.txt", "a") as logFile: + with open(self.home+"/.WebControl/"+"alog.txt", "a") as logFile: logFile.write(toWrite) return + def deleteLogFiles(self): + """ + Delete log files + """ + success1 = False + for x in range(0, 1000): + try: + os.remove(self.home+"/.WebControl/"+"log.txt") + success1 = True + break + except: + success1 = False + + success2 = False + for x in range(0, 1000): + try: + os.remove(self.home+"/.WebControl/"+"alog.txt") + success2 = True + break + except: + success2 = False + + if success1 and success2: + return True + else: + return False + def writeErrorValueToLog(self, error): """ @@ -109,7 +210,7 @@ def endRecordingAvgError(self): Stops recording error values. """ - print("stopping to record") + self.data.console_queue.put("stopping to record") self.recordingPositionalErrors = False def reportAvgError(self): @@ -120,7 +221,7 @@ def reportAvgError(self): """ avg = sum(self.errorValues) / len(self.errorValues) - self.data.ui_queue.put( + self.data.ui_controller_queue.put( "Message: The average feedback system error was: " + "%.2f" % avg + "mm" ) diff --git a/DataStructures/uiQueue.py b/DataStructures/uiQueue.py new file mode 100644 index 00000000..b095699d --- /dev/null +++ b/DataStructures/uiQueue.py @@ -0,0 +1,43 @@ +""" + +This module provides a simple addition to the Queue, which is that it logs +puts to the Queue immediately. + +""" + +from queue import Queue +import json + + +class UIQueue(Queue): + def __init__(self): + super(UIQueue, self).__init__() + + def put(self, command, message, dictionary): + ''' + This is an attempt to standardize on the communications format. There's probably a fair amount of work that + should go into updating this. The concept is that there are three elements: + :param command: The type/command of the message + :param message: The actual message + :param dictionary: Values/Arguments that accompany the message + :return: + Some times things don't come across correctly, particularly text messages from the controller. need to work + on this and document it better. + All three of the elements get converted into a single json string for insertion into the queue + ''' + #if command == "TextMessage" or command == "Alert": + # data = dictionary # these are text lines, so no need to jsonify + #else: + try: + # convert the dictionary to a json + data = json.dumps(dictionary) + except Exception as e: + print("####") + print(e) + print("####") + + # convert the command, message, and jsonified dictionary into a json + msg = json.dumps({"command": command, "message": message, "data": data}) + + # put in uiqueue + return super(UIQueue, self).put(msg) diff --git a/Dockerfile b/Dockerfile index 20ebcdb3..3f88cc62 100644 --- a/Dockerfile +++ b/Dockerfile @@ -1,8 +1,7 @@ -FROM python:3.5.6-slim-stretch +FROM arm32v7/python:3.5.6-slim-stretch as builder # Install dependencies needed for building and running OpenCV -RUN apt-get update -RUN apt-get install -y --no-install-recommends \ +RUN apt-get update && apt-get install -y --no-install-recommends \ # to build and install unzip wget sed \ build-essential cmake pkg-config \ @@ -17,12 +16,15 @@ RUN apt-get install -y --no-install-recommends \ # libtbb2 libtbb-dev \ # for gevent libevent-dev \ + # for numpy (installs libf77blas.so.3) + libatlas-base-dev \ # cleanup && rm -rf /var/lib/apt/lists/* \ && apt-get -y autoremove # OpenCV dependency -RUN pip install numpy +RUN pip install numpy==1.16.2 +RUN pip install scipy==1.3.1 # Build OpenCV ADD tools/download_build_install_opencv.sh /download_build_install_opencv.sh @@ -30,15 +32,93 @@ RUN chmod +x /download_build_install_opencv.sh && /download_build_install_opencv # Get other python dependencies ADD requirements.txt /requirements.txt -# Remove opencv from requirements (use the compiled one) -RUN sed -i '/opencv-python.*/d' /requirements.txt -RUN pip install -r /requirements.txt +# Remove opencv, scipy and numpy from requirements (since they're already installed) +RUN sed -i '/opencv-python.*/d' /requirements.txt && sed -i '/scipy.*/d' /requirements.txt && sed -i '/numpy.*/d' /requirements.txt +# TODO: Maybe we can cache wheel files outside this container, for more granular reuse when requiremnts.txt changes +RUN pwd +RUN apt-get update && apt-get install -y --no-install-recommends python-dev libffi-dev +RUN pip install -r /requirements.txt + +# Download and compile the Arduino firmware +# Generates the firmware as /firmware/.pioenvs/megaatmega2560/firmware.hex +# PlatformIO doesn't support python3 yet, so also install python2 :/ +# See also: https://github.com/platformio/platformio-core/issues/895 +RUN apt-get update \ + && apt-get install -y --no-install-recommends python2.7 python-pip python-setuptools python-wheel git \ + && pip2 install -U platformio \ + && pio platform install --with-package framework-arduino atmelavr \ + && pio lib -g install "Servo" + + +ARG madgrizzle_firmware_repo=https://github.com/madgrizzle/Firmware.git +ARG madgrizzle_firmware_sha=bf4350ffd9bc154832505fc0125abd2c4c04dba7 +#ARG madgrizzle_firmware_sha=95f7d4b5c431dec162d2e2eec7c6e42530298c4b +RUN git clone $madgrizzle_firmware_repo firmware/madgrizzle \ + && cd firmware/madgrizzle \ + && git checkout $madgrizzle_firmware_sha \ + && pio run -e megaatmega2560 \ + && mkdir build \ + && mv .pio/build/megaatmega2560/firmware.hex build/$madgrizzle_firmware_sha-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex +ARG maslowcnc_firmware_repo=https://github.com/MaslowCNC/Firmware.git +ARG maslowcnc_firmware_sha=e1e0d020fff1f4f7c6b403a26a85a16546b7e15b +RUN git clone $maslowcnc_firmware_repo firmware/maslowcnc \ + && cd firmware/maslowcnc \ + && git checkout $maslowcnc_firmware_sha \ + && pio run -e megaatmega2560 \ + && mkdir build \ + && mv .pio/build/megaatmega2560/firmware.hex build/$maslowcnc_firmware_sha-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex +RUN pwd +ARG holey_firmware_repo=https://github.com/madgrizzle/Firmware.git +ARG holey_firmware_sha=950fb23396171cbd456c2d4149455cc45f5e6bc3 +RUN git clone $holey_firmware_repo firmware/holey \ + && cd firmware/holey \ + && git checkout $holey_firmware_sha \ + && pio run -e megaatmega2560 \ + && mkdir build \ + && mv .pio/build/megaatmega2560/firmware.hex build/$holey_firmware_sha-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex -# Remove no-longer-needed gevent compilation libraries -RUN apt-get purge -y --auto-remove --allow-remove-essential gcc libevent-dev wget unzip sed -# Copy the source ADD . /WebControl +# Clean up the /WebControl dir a bit to slim it down +# TODO: Is there a more automatic way to do this? +RUN rm -rf /WebControl/.venv && rm -rf /WebControl/.git +# Pre-compile the pyc files (for faster Docker image startup) +RUN python --version && python -m compileall /WebControl + + +FROM arm32v7/python:3.5.6-slim-stretch + +# Pip wheels compiled in the builder +COPY --from=builder /root/.cache /root/.cache +# requirements.txt with opencv, scipy and numpy removed +COPY --from=builder /requirements.txt /requirements.txt +# Required shared libraries +COPY --from=builder /usr/local/lib/python3.5/site-packages/cv2.cpython-35m-arm-linux-gnueabihf.so /usr/local/lib/python3.5/site-packages/cv2.cpython-35m-arm-linux-gnueabihf.so +COPY --from=builder /usr/lib/libf77blas.so /usr/lib/libf77blas.so +COPY --from=builder /usr/lib/libf77blas.so.3 /usr/lib/libf77blas.so.3 +COPY --from=builder /usr/lib/libcblas.so.3 /usr/lib/libcblas.so.3 +COPY --from=builder /usr/lib/libatlas.so.3 /usr/lib/libatlas.so.3 +COPY --from=builder /usr/lib/libblas.so.3 /usr/lib/libblas.so.3 +COPY --from=builder /usr/lib/arm-linux-gnueabihf/libgfortran.so.3 /usr/lib/arm-linux-gnueabihf/libgfortran.so.3 +COPY --from=builder /usr/lib/liblapack.so.3 /usr/lib/liblapack.so.3 + +RUN pip install numpy==1.16.2 && pip install scipy==1.3.1 && pip install -r /requirements.txt && rm -rf /root/.cache + + +# Install avrdude +# TODO: to speed up incremental docker builds, we can probably do this in the builder image if we can figure out +# which files we need to copy over +RUN apt-get update && apt-get install -y --no-install-recommends \ + avrdude \ + && rm -rf /var/lib/apt/lists/* \ + && apt-get -y autoremove +# Copy in the pre-compiled firmware +COPY --from=builder /firmware/madgrizzle/build/* /firmware/madgrizzle/ +COPY --from=builder /firmware/holey/build/* /firmware/holey/ +COPY --from=builder /firmware/maslowcnc/build/* /firmware/maslowcnc/ + +# Copy the pre-compiled source from the builder +COPY --from=builder /WebControl /WebControl WORKDIR /WebControl EXPOSE 5000/tcp diff --git a/File/gcodeFile.py b/File/gcodeFile.py index a5a8376d..a134945a 100644 --- a/File/gcodeFile.py +++ b/File/gcodeFile.py @@ -5,6 +5,8 @@ import json import re import math +import gzip +import io class Line: @@ -13,17 +15,20 @@ def __init__(self): self.color = None self.dashed = False self.type = None + self.radius = None + self.command = None class GCodeFile(MakesmithInitFuncs): isChanged = False canvasScaleFactor = 1 # scale from mm to pixels INCHES = 1.0 - MILLIMETERS = 1.0 / 25.4 + MILLIMETERS = 1.0/25.4 xPosition = 0 yPosition = 0 zPosition = 0 + truncate = -1 #do this to truncate after shift of home position lineNumber = 0 # the line number currently being processed @@ -34,32 +39,100 @@ class GCodeFile(MakesmithInitFuncs): maxNumberOfLinesToRead = 300000 filename = "" - line = [] + line3D = [] + ''' + prependString is defined here so it can be persistent across each 'moveOneLine'. That way, if a gcode line + does not contain a valid gcode, it uses the previous line's gcode. Thanks to @amantalion for discovering the + glitch. https://github.com/madgrizzle/WebControl/issues/78 + ''' + prependString = "" - def serializeGCode(self): - sendStr = json.dumps([ob.__dict__ for ob in self.data.gcodeFile.line]) + + def serializeGCode3D(self): + sendStr = json.dumps([ob.__dict__ for ob in self.data.gcodeFile.line3D]) return sendStr - def loadUpdateFile(self): - filename = self.data.gcodeFile.filename - # print(filename) - del self.line[:] - if filename is "": # Blank the g-code if we're loading "nothing" - self.data.gcode = "" + def saveFile(self, fileName, directory): + if fileName is "": # Blank the g-code if we're loading "nothing" + return False + if directory is "": return False - try: - filterfile = open(filename, "r") + homeX = float(self.data.config.getValue("Advanced Settings", "homeX")) + homeY = float(self.data.config.getValue("Advanced Settings", "homeY")) + fileToWrite = directory + "/" + fileName + gfile = open(fileToWrite, "w+") + print(fileToWrite) + for line in self.data.gcode: + gfile.write(line+'\n') + #gfile = open(directory+fileName, "w+") + #gfile.writelines(map(lambda s: s+ '\n', self.data.gcode)) + print("Closing File") + gfile.close() + except Exception as e: + self.data.console_queue.put(str(e)) + self.data.console_queue.put("Gcode File Error") + self.data.ui_queue1.put("Alert", "Alert", "Cannot save gcode file.") + self.data.gcodeFile.filename = "" + return False + return True + + def loadUpdateFile(self, gcode=""): + print("At loadUpdateFile") + gcodeLoad = False + if gcode=="": + gcodeLoad = True + if self.data.units == "MM": + self.canvasScaleFactor = self.MILLIMETERS + print("units in mm") + else: + self.canvasScaleFactor = self.INCHES + print("units inches") + self.data.clidisplay = self.data.config.getValue("Maslow Settings", "clidisplay") + print ("clidisplay is ", self.data.clidisplay) + if (self.data.clidisplay): + self.data.gcode_x_min = 2000 + self.data.gcode_x_max = -2000 + self.data.gcode_y_min = 1000 + self.data.gcode_y_max = -1000 + self.data.gcode_z_min = 20 + self.data.gcode_z_max = -20 + print("reset gcode coordinates") + if gcode == "": + filename = self.data.gcodeFile.filename + self.data.gcodeShift[0] = round(float(self.data.config.getValue("Advanced Settings", "homeX")),4) + self.data.gcodeShift[1] = round(float(self.data.config.getValue("Advanced Settings", "homeY")),4) + del self.line3D[:] + if filename is "": # Blank the g-code if we're loading "nothing" + self.data.gcode = "" + return False + + try: + filterfile = open(filename, "r") + except Exception as e: + self.data.console_queue.put(str(e)) + self.data.console_queue.put("Gcode File Error") + self.data.ui_queue1.put("Alert", "Alert", "Cannot open gcode file.") + self.data.gcodeFile.filename = "" + return False rawfilters = filterfile.read() - filtersparsed = re.sub( - r"\(([^)]*)\)", "\n", rawfilters - ) # replace mach3 style gcode comments with newline + filterfile.close() # closes the filter save file + else: + del self.line3D[:] + rawfilters = gcode + + try: + if True: #this is just for testing R removal + filtersparsed = rawfilters #get rid of this if above is uncommented) + ''' filtersparsed = re.sub( r";([^\n]*)\n", "\n", filtersparsed ) # replace standard ; initiated gcode comments with newline + ''' + #print(filtersparsed) filtersparsed = re.sub(r"\n\n", "\n", filtersparsed) # removes blank lines filtersparsed = re.sub( - r"([0-9])([GXYZIJFTM]) *", "\\1 \\2", filtersparsed + r"([0-9])([GXYZIJFTMR]) *", "\\1 \\2", filtersparsed ) # put spaces between gcodes filtersparsed = re.sub(r" +", " ", filtersparsed) # condense space runs value = self.data.config.getValue("Advanced Settings", "truncate") @@ -69,57 +142,157 @@ def loadUpdateFile(self): filtersparsed = re.sub( r"([+-]?\d*\.\d{1," + digits + "})(\d*)", r"\g<1>", filtersparsed ) # truncates all long floats to 4 decimal places, leaves shorter floats - filtersparsed = re.split( - "\n", filtersparsed - ) # splits the gcode into elements to be added to the list - filtersparsed = [ - x + " " for x in filtersparsed - ] # adds a space to the end of each line - filtersparsed = [x.lstrip() for x in filtersparsed] + self.truncate = int(digits) + else: + self.truncate = -1 + filtersparsed = re.split("\n", filtersparsed) # splits the gcode into elements to be added to the list + filtersparsed = [x.lstrip() for x in filtersparsed] # remove leading spaces + filtersparsed = [x + " " for x in filtersparsed] # adds a space to the end of each line filtersparsed = [x.replace("X ", "X") for x in filtersparsed] filtersparsed = [x.replace("Y ", "Y") for x in filtersparsed] filtersparsed = [x.replace("Z ", "Z") for x in filtersparsed] filtersparsed = [x.replace("I ", "I") for x in filtersparsed] filtersparsed = [x.replace("J ", "J") for x in filtersparsed] filtersparsed = [x.replace("F ", "F") for x in filtersparsed] + filtersparsed = [x.replace("R ", "R") for x in filtersparsed] + #print (filtersparsed) + #((\%)|((?PN\s*\d{1,5})?\s*(?P[ABCDFGHIJKLMNPRSTXYZ]\s*[+-]?(\d|\s)*\.?(\d|\s)*\s*)|(?P\(.*?\)\s*))) + for index, line in enumerate(filtersparsed): + R = re.search("R(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", line) + if R: #R will crash the arduino, so change the G02 G03 to G01 + piece = line + print("line: ", line) + if (line.find("G03")!=-1): + newpiece = piece.replace("G03","G01") + Index1 = newpiece.split("R") #remove after R + newpiece = Index1[0] + print ("G3 replace",newpiece) + filtersparsed[index] = newpiece + if (line.find("G02")!=-1): + cut2line = piece.replace("G02","G01") + Index1 = cut2line.split("R") #remove after R + cut2line = Index1[0] + print ("G03 replace", cut2line) + filtersparsed[index] = cut2line + #print ("took out the G02 and G03: ", filtersparsed) + if (self.data.clidisplay): + X = re.search("X(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", line) + Y = re.search("Y(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", line) + if (type(X) != None): + if X: # find min and max of X values + q = abs(float(X.groups()[0])) + self.displayX(q) + if (type(Y) != None): + if Y: # find min and max of Y values + q = abs(float(Y.groups()[0])) + self.displayY(q) self.data.gcode = "[]" self.data.gcode = filtersparsed - - filterfile.close() # closes the filter save file # Find gcode indicies of z moves self.data.zMoves = [0] zList = [] for index, line in enumerate(self.data.gcode): - z = re.search("Z(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", line) - if z: - zList.append(z) - if len(zList) > 1: - if not self.isClose( - float(zList[-1].groups()[0]), float(zList[-2].groups()[0]) - ): - self.data.zMoves.append(index - 1) - else: - self.data.zMoves.append(index) - except: - print("Gcode File Error") - self.data.ui_queue.put("Message: Cannot open gcode file.") - self.data.gcodeFile = "" + filtersparsed = re.sub(r'\(([^)]*)\)', '', line) # replace mach3 style gcode comments with newline + line = re.sub(r';([^\n]*)?', '\n',filtersparsed) # replace standard ; initiated gcode comments with newline + if not line.isspace(): # if all spaces, don't send. likely a comment. #if line.find("(") == -1: + if line.find("G20") != -1: + self.data.tolerance = 0.020 + self.data.config.setValue("Computed Settings", "tolerance", self.data.tolerance) + if line.find("G21") != -1: + self.data.tolerance = 0.50 + self.data.config.setValue("Computed Settings", "tolerance", self.data.tolerance) + z = re.search("Z(?=.)([+-]?([0-9]*)(\.([0-9]+))?)", line) + if z: + zList.append(z) + if len(zList) > 1: + if not self.isClose( + float(zList[-1].groups()[0]), float(zList[-2].groups()[0]) + ): + self.data.zMoves.append(index) # - 1) + else: + self.data.zMoves.append(index) + pass + except Exception as e: + self.data.console_queue.put(str(e)) + self.data.console_queue.put("Gcode File Error") + self.data.ui_queue1.put("Alert", "Alert", "Cannot open gcode file.") + self.data.gcodeFile.filename = "" return False self.updateGcode() self.data.gcodeFile.isChanged = True + self.data.actions.sendGCodePositionUpdate(self.data.gcodeIndex, recalculate=True) return True - + + def displayX(self,x): + ''' + get max and min X then offset from defined home position + ''' + newm = x*self.canvasScaleFactor #+ float(self.data.config.getValue("Advanced Settings", "homeX")) + bedwidth = round(float(self.data.config.getValue("Maslow Settings", "bedWidth")),4) + if (newm > bedwidth): + newm = bedwidth + print("Off Right") + if (newm < (0-bedwidth)): + newm = 0 - bedwidth + print("Off Left") + if (newm < self.data.gcode_x_min): + self.data.gcode_x_min = newm + print("calculating new min X ", newm) + if (newm > self.data.gcode_x_max): + self.data.gcode_x_max = newm + print("calculating new max X ", newm) + #print("calculating X ", x) + + def displayY(self,y): + ''' + check min and max Y values against each Y point for line draw or arc draw + ''' + newm = y*self.canvasScaleFactor #+ float(self.data.config.getValue("Advanced Settings", "homeY")) + height = round(float(self.data.config.getValue("Maslow Settings", "bedHeight")),4) + if (newm > height): + newm = height + print("overheight") + if (newm < (0-height)): + newm = 0 - height + print("Underbound") + if (newm > self.data.gcode_y_max): + self.data.gcode_y_max = newm + print("calculating new max Y ", newm) + if (newm < self.data.gcode_y_min): + self.data.gcode_y_min = newm + print("calculating new min Y ", newm) + + def displayZ(self,z): + ''' + check min and max z values + ''' + if (z < self.data.gcode_z_min): + self.data.gcode_z_min = z + if (z > self.data.gcode_z_max): + self.data.gcode_z_max = z + def isClose(self, a, b): return abs(a - b) <= self.data.tolerance - def addPoint(self, x, y): + '''def addPoint(self, x, y): """ Add a point to the line currently being plotted """ self.line[-1].points.append( - (x * self.canvasScaleFactor, y * self.canvasScaleFactor * -1.0) + #(x * self.canvasScaleFactor, y * self.canvasScaleFactor * -1.0) + (x , y * -1.0) + ) + ''' + + def addPoint3D(self, x, y, z): + """ + Add a point to the line currently being plotted + """ + self.line3D[-1].points.append( + (x, y, z) ) + def isNotReallyClose(self, x0, x1): if abs(x0 - x1) > 0.0001: return True @@ -146,72 +319,157 @@ def drawLine(self, gCodeLine, command): xTarget = float(x.groups()[0]) * self.canvasScaleFactor if self.absoluteFlag == 1: xTarget = self.xPosition + xTarget + #print("x ", self.xPosition, " x target ", xTarget) + #if (self.data.clidisplay): + # self.displayX(xTarget) y = re.search("Y(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) if y: yTarget = float(y.groups()[0]) * self.canvasScaleFactor if self.absoluteFlag == 1: yTarget = self.yPosition + yTarget + #print("y ", self.yPosition, " y Target ", yTarget) + #if (self.data.clidisplay): + # self.displayY(yTarget) + z = re.search("Z(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) if z: zTarget = float(z.groups()[0]) * self.canvasScaleFactor - - # Draw lines for G1 and G0 - # with self.scatterObject.canvas: - # print "Command:"+command - # print "#"+gCodeLine+"#" - # print "#"+str(self.xPosition/25.4)+", "+str(self.yPosition/25.4)+" - "+str(xTarget/25.4)+", "+str(yTarget/25.4) + #if (self.data.clidisplay): + # self.displayZ(zTarget) if self.isNotReallyClose(self.xPosition, xTarget) or self.isNotReallyClose( self.yPosition, yTarget ): - # Color(self.data.drawingColor[0], self.data.drawingColor[1], self.data.drawingColor[2]) if command == "G00": # draw a dashed line - self.line.append(Line()) # points = (), width = 1, group = 'gcode') - self.line[-1].type = "line" - self.line[-1].dashed = True - self.addPoint(self.xPosition, self.yPosition) - self.addPoint(xTarget, yTarget) + + self.line3D.append(Line()) # points = (), width = 1, group = 'gcode') + self.line3D[-1].type = "line" + self.line3D[-1].command = None + self.line3D[-1].dashed = True + self.addPoint3D(self.xPosition, self.yPosition, self.zPosition) + self.addPoint3D(xTarget, yTarget, zTarget) + else: - # print "here" - if ( - len(self.line) == 0 - or self.line[-1].dashed - or self.line[-1].type != "line" - ): - self.line.append( - Line() - ) # points = (), width = 1, group = 'gcode') - self.line[-1].type = "line" - self.addPoint(self.xPosition, self.yPosition) - self.line[-1].dashed = False - self.addPoint(xTarget, yTarget) + if (len(self.line3D) == 0 or self.line3D[-1].dashed or self.line3D[-1].type != "line"): #test123 + self.line3D.append( Line() ) + self.line3D[-1].type = "line" + self.line3D[-1].command = None + self.addPoint3D(self.xPosition, self.yPosition, self.zPosition) + self.line3D[-1].dashed = False + + + self.addPoint3D(xTarget, yTarget, zTarget) # If the zposition has changed, add indicators tol = 0.05 # Acceptable error in mm if abs(zTarget - self.zPosition) >= tol: - # with self.scatterObject.canvas: if True: if zTarget - self.zPosition > 0: # Color(0, 1, 0) - radius = 1 + radius = 2 else: # Color(1, 0, 0) - radius = 2 - self.line.append(Line()) # points = (), width = 1, group = 'gcode') - self.line[-1].type = "circle" - self.addPoint(self.xPosition, self.yPosition) - self.addPoint(radius, 0) - self.line[-1].dashed = False - # Line(circle=(self.xPosition , self.yPosition, radius), group = 'gcode') - # Color(self.data.drawingColor[0], self.data.drawingColor[1], self.data.drawingColor[2]) + radius = 1 + self.line3D.append(Line()) # points = (), width = 1, group = 'gcode') + self.line3D[-1].type = "circle" + self.line3D[-1].command = None + self.addPoint3D(self.xPosition, self.yPosition, self.zPosition) + self.addPoint3D(radius, 0, zTarget) #targetOut + self.line3D[-1].dashed = False + #print("cli display",self.data.clidisplay) + #if (self.data.clidisplay): + # self.displayX(self.xPosition) + #if (self.data.clidisplay): + # self.displayY(self.yPosition) self.xPosition = xTarget self.yPosition = yTarget self.zPosition = zTarget - # except: - # print "Unable to draw line on screen: " + gCodeLine + + def drawMCommand(self, mString): + """ + + drawToolChange draws a circle indicating a tool change. + + """ + #print(mString) + code = self.getMCommand(mString) + #print(code) + #code = mString[1:2] #just the number? + circleSize = 0 + arg = 0 + command = None + if code == 3: + arg = self.getSpindleSpeed(mString) + if arg == 0: + circleSize = 5 + command = "SpindleOff" + else: + circleSize = 3 + command = "SpindleOnCW" + if code == 4: + arg = self.getSpindleSpeed(mString) + if arg == 0: + circleSize = 5 + command = "SpindleOff" + else: + circleSize = 4 + command = "SpindleOnCCW" + if code == 5: # Spindle Stop + circleSize = 5 + command = "SpindleOff" + if code == 6: # Tool Change + circleSize = 6 + command = "ToolChange" + arg = self.currentDrawTool + + self.line3D.append(Line()) # points = (), width = 1, group = 'gcode') + self.line3D[-1].type = "circle" + self.line3D[-1].command = command + self.addPoint3D(self.xPosition, self.yPosition, self.zPosition) + self.addPoint3D(circleSize, arg, self.zPosition) + self.line3D[-1].dashed = False + + def getSpindleSpeed(self, mString): + code = mString[mString.find("S")+1:] + try: + if code!="": + return float(code) + else: + return 0 + except: + return -1 + + def getToolNumber(self, mString): + code0 = mString.find("T") + code1 = mString.find("M") + code = mString[code0+1:code1-code0] + #print(mString) + #print(code) + try: + if code!="": + return int(code) + else: + return 0 + except: + return -1 + + def getMCommand(self, mString): + code0 = mString.find("M") + code1 = mString.find(" ", code0) + if code1 == -1: + code1 = mString.find("T", code0) + if code1 == -1: + code = mString[code0+1:] + else: + code = mString[code0+1: code1-code0] + if code!="": + return int(code) + else: + return 0 + def drawArc(self, gCodeLine, command): """ @@ -225,22 +483,34 @@ def drawArc(self, gCodeLine, command): if True: xTarget = self.xPosition yTarget = self.yPosition + zTarget = self.zPosition iTarget = 0 jTarget = 0 x = re.search("X(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) if x: xTarget = float(x.groups()[0]) * self.canvasScaleFactor + #if (self.data.clidisplay): + # self.displayX(xTarget) + y = re.search("Y(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) if y: yTarget = float(y.groups()[0]) * self.canvasScaleFactor + #if (self.data.clidisplay): + # self.displayY(yTarget) + i = re.search("I(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) if i: iTarget = float(i.groups()[0]) * self.canvasScaleFactor + j = re.search("J(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) if j: jTarget = float(j.groups()[0]) * self.canvasScaleFactor - + + z = re.search("Z(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + if z: + zTarget = float(z.groups()[0]) * self.canvasScaleFactor + radius = math.sqrt(iTarget ** 2 + jTarget ** 2) centerX = self.xPosition + iTarget centerY = self.yPosition + jTarget @@ -269,28 +539,28 @@ def drawArc(self, gCodeLine, command): arcLen = 6.28313530718 if ( - len(self.line) == 0 - or self.line[-1].dashed - or self.line[-1].type != "line" + len(self.line3D) == 0 + or self.line3D[-1].dashed + or self.line3D[-1].type != "line" ): - self.line.append(Line()) # points = (), width = 1, group = 'gcode') - self.addPoint(self.xPosition, self.yPosition) - self.line[-1].type = "line" - self.line[-1].dashed = False - + self.line3D.append(Line()) # points = (), width = 1, group = 'gcode') + self.addPoint3D(self.xPosition, self.yPosition, self.zPosition) + self.line3D[-1].type = "line" + self.line3D[-1].dashed = False + zStep = (zTarget - self.zPosition)/math.fabs(arcLen/(.1*direction)) i = 0 + counter = 0 while abs(i) < arcLen: xPosOnLine = centerX + radius * math.cos(angle1 + i) yPosOnLine = centerY + radius * math.sin(angle1 + i) - self.addPoint(xPosOnLine, yPosOnLine) + zPosOnLine = self.zPosition + zStep*counter + self.addPoint3D(xPosOnLine, yPosOnLine, zPosOnLine) i = i + 0.1 * direction # this is going to need to be a direction - - self.addPoint(xTarget, yTarget) - + counter+=1 + self.addPoint3D(xTarget, yTarget, zTarget) self.xPosition = xTarget self.yPosition = yTarget - # except: - # print "Unable to draw arc on screen: " + gCodeLine + self.zPosition = zTarget def clearGcode(self): """ @@ -298,66 +568,117 @@ def clearGcode(self): clearGcode deletes the lines and arcs corresponding to gcode commands from the canvas. """ - del self.line[:] - def moveLine(self, gCodeLine): + del self.line3D[:] - originalLine = gCodeLine + def clearGcodeFile(self): + """ - try: - gCodeLine = gCodeLine.upper() + " " - x = re.search("X(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) - if x: - # xTarget = '%f' % (float(x.groups()[0]) + self.data.gcodeShift[0]) # not used any more... - - eNtnX = re.sub( - "\-?\d\.|\d*e-", - "", - str(abs(float(x.groups()[0]) + self.data.gcodeShift[0])), - ) # strip off everything but the decimal part or e-notation exponent - e = re.search( - ".*e-", str(abs(float(x.groups()[0]) + self.data.gcodeShift[0])) - ) - if e: - fmtX = ( - "%0%.%sf" % eNtnX - ) # if e-notation, use the exponent from the e notation - else: - fmtX = "%0%.%sf" % len( - eNtnX - ) # use the number of digits after the decimal place - gCodeLine = ( - gCodeLine[0 : x.start() + 1] - + (fmtX % (float(x.groups()[0]) + self.data.gcodeShift[0])) - + gCodeLine[x.end() :] - ) + clearGcodeFile deletes the lines and arcs and the file - y = re.search("Y(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) - if y: - # yTarget = '%f' % (float(y.groups()[0]) + self.data.gcodeShift[1]) # not used any more... - eNtnY = re.sub( - "\-?\d\.|\d*e-", - "", - str(abs(float(y.groups()[0]) + self.data.gcodeShift[1])), - ) - e = re.search( - ".*e-", str(abs(float(y.groups()[0]) + self.data.gcodeShift[1])) - ) - if e: - fmtY = "%0%.%sf" % eNtnY - else: - fmtY = "%0%.%sf" % len(eNtnY) - gCodeLine = ( - gCodeLine[0 : y.start() + 1] - + (fmtY % (float(y.groups()[0]) + self.data.gcodeShift[1])) - + gCodeLine[y.end() :] - ) - - return gCodeLine - except ValueError: - print("line could not be moved:") - print(originalLine) - return originalLine + """ + + del self.line3D[:] + + self.data.gcode = [] + self.updateGcode() + self.data.gcodeFile.isChanged = True + + def moveLine(self, gCodeLine): + + originalLine = gCodeLine + shiftX = self.data.gcodeShift[0] + shiftY = self.data.gcodeShift[1] + if len(gCodeLine) > 0: + if gCodeLine[0] == '(' or gCodeLine[0] == ';': + return originalLine + #next check for comment after line and if exist, split on first occurrence and retain the comment portion + findexA = gCodeLine.find('(') + findexB = gCodeLine.find(';') + #check to see which came first.. who knows, maybe someone used a ; within a ( + if findexA != -1 and findexA < findexB: + findex = findexA + else: + findex = findexB + comment = "" + if findex != -1: + #found comment at findex + comment = gCodeLine[findex:] + #print("comment:"+comment) + gCodeLine = gCodeLine[:findex] + + #This test should always pass so taking it out + #if gCodeLine.find("(") == -1 and gCodeLine.find(";") == -1: + if True: + try: + gCodeLine = gCodeLine.upper() + " " + x = re.search("X(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + if x: + q = abs(float(x.groups()[0])+shiftX) + if self.truncate >= 0: + q = str(round(q, self.truncate)) + else: + q = str(q) + + eNtnX = re.sub("\-?\d\.|\d*e-","",q,) # strip off everything but the decimal part or e-notation exponent + + e = re.search(".*e-", q) + + if (self.data.pythonVersion35 == False): + if e: + fmtX = "%0.{0}f".format(eNtnX) + else: + fmtX = "%0.{0}f".format(len(eNtnX)) + else: #deprecated python 3.6 + if e: + fmtX = ("%0%.%sf" % eNtnX) # if e-notation, use the exponent from the e notation + else: + fmtX = "%0%.%sf" % len(eNtnX) # use the number of digits after the decimal place + gCodeLine = ( + gCodeLine[0 : x.start() + 1] + + (fmtX % (float(x.groups()[0]) + shiftX)) + + gCodeLine[x.end() :] + ) + #if (self.data.clidisplay): + # self.displayX(fmtX % (float(x.groups()[0]) + shiftX)) + + y = re.search("Y(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + if y: + q = abs(float(y.groups()[0])+shiftY) + if self.truncate >= 0: + q = str(round(q, self.truncate)) + else: + q = str(q) + + eNtnY = re.sub("\-?\d\.|\d*e-", "", q, ) + + e = re.search(".*e-", q ) + if (self.data.pythonVersion35 == False): + if e: + fmtY = "%0.{0}f".format(eNtnY) + else: + fmtY = "%0.{0}f".format(len(eNtnY)) + else: #deprecated python 3.6 + if e: + fmtY = ("%0%.%sf" % eNtnY) # if e-notation, use the exponent from the e notation + else: + fmtY = "%0%.%sf" % len(eNtnY) # use the number of digits after the decimal place + gCodeLine = ( + gCodeLine[0 : y.start() + 1] + + (fmtY % (float(y.groups()[0]) + shiftY)) + + gCodeLine[y.end() :] + ) + #if (self.data.clidisplay): + # self.displayY(fmtY % (float(y.groups()[0]) + shiftY)) + #now, put any comment back. + gCodeLine = gCodeLine+comment + return gCodeLine + except ValueError: + self.data.console_queue.put("line could not be moved:") + print(originalLine) + self.data.console_queue.put(originalLine) + return originalLine + return originalLine def loadNextLine(self): """ @@ -367,22 +688,21 @@ def loadNextLine(self): """ try: - self.data.gcode[self.lineNumber] = self.moveLine( - self.data.gcode[self.lineNumber] - ) # move the line if the gcode has been moved fullString = self.data.gcode[self.lineNumber] except: return # we have reached the end of the file + filtersparsed = re.sub(r'\(([^)]*)\)', '\n', fullString) # replace mach3 style gcode comments with newline + #fullString = re.sub(r';([^\n]*)\n', '\n', filtersparsed) # replace standard ; initiated gcode comments with newline + fullString = re.sub(r';([^\n]*)?', '\n', filtersparsed) # replace standard ; initiated gcode comments with newline + #print("fullString:"+fullString) # if the line contains multiple gcode commands split them and execute them individually listOfLines = fullString.split("G") if len(listOfLines) > 1: # if the line contains at least one 'G' for line in listOfLines: if len(line) > 0: # If the line is not blank - # print "line:"+str(self.lineNumber)+"#G"+str(line)+"#" self.updateOneLine("G" + line) # Draw it else: - # print "line:"+str(self.lineNumber)+"<"+fullString+">" self.updateOneLine(fullString) self.lineNumber = self.lineNumber + 1 @@ -409,9 +729,8 @@ def updateOneLine(self, fullString): fullString = ( fullString + " " ) # ensures that there is a space at the end of the line - # find 'G' anywhere in string - self.prependString = "" + gString = fullString[fullString.find("G") : fullString.find("G") + 3] if gString in validPrefixList: @@ -441,15 +760,21 @@ def updateOneLine(self, fullString): pass if gString == "G18": - print("G18 not supported") + self.data.console_queue.put("G18 not supported") if gString == "G20": + #print(fullString) + if self.data.units != "INCHES": + self.data.actions.updateSetting("toInches", 0, True) # value = doesn't matter self.canvasScaleFactor = self.INCHES - # self.data.units = "INCHES" + self.data.gcodeFileUnits = "INCHES" if gString == "G21": + # print(fullString) + if self.data.units != "MM": + self.data.actions.updateSetting("toMM", 0, True) #value = doesn't matter + self.data.gcodeFileUnits = "MM" self.canvasScaleFactor = self.MILLIMETERS - # self.data.units = "MM" if gString == "G90": self.absoluteFlag = 0 @@ -457,58 +782,52 @@ def updateOneLine(self, fullString): if gString == "G91": self.absoluteFlag = 1 - def callBackMechanism(self, callback): - """ + #tString = fullString[fullString.find("T") : fullString.find("T") + 2] + tString = fullString[fullString.find("T") :] + if tString.find("T") != -1: + self.currentDrawTool = self.getToolNumber(tString) + + mString = fullString[fullString.find("M") : ] + if mString.find("M") != -1: + self.drawMCommand(mString) - Call the loadNextLine function periodically in a non-blocking way to - update the gcode. + def callBackMechanism(self): + """ + Call the loadNextLine function in background. """ - # with self.scatterObject.canvas: + for _ in range(min(len(self.data.gcode), self.maxNumberOfLinesToRead)): + self.loadNextLine() - # self.line.append(Line()) #Line(points = (), width = 1, group = 'gcode') + tstr = json.dumps([ob.__dict__ for ob in self.data.gcodeFile.line3D]) + out = io.BytesIO() + with gzip.GzipFile(fileobj=out, mode="w") as f: + f.write(tstr.encode()) + self.data.compressedGCode3D = out.getvalue() - # Draw numberOfTimesToCall lines on the canvas - # print "here:"+str(self.lineNumber) - numberOfTimesToCall = 500 - for _ in range(numberOfTimesToCall): - self.loadNextLine() + self.data.console_queue.put("uncompressed:"+str(len(tstr))) + self.data.console_queue.put("compressed3D:"+str(len(self.data.compressedGCode3D))) - # Repeat until end of file - # print "end:"+str(self.lineNumber) - # print self.lineNumber - # print len(self.data.gcode) - # print self.maxNumberOfLinesToRead - if self.lineNumber < min(len(self.data.gcode), self.maxNumberOfLinesToRead): - # print "here" - self.callBackMechanism(self.updateGcode) - if True: - for line in self.line: - _str = ( - "Type:" - + str(line.type) - + ", Color:" - + str(line.color) - + ", Dashed:" - + str(line.dashed) - + "..." - ) - for point in line.points: - _str += str(point) - # print _str def updateGcode(self): """ updateGcode parses the gcode commands and calls the appropriate drawing function for the specified command. """ - # print "Here at updateGcode" - # reset variables self.data.backgroundRedraw = False - self.xPosition = self.data.gcodeShift[0] * self.canvasScaleFactor - self.yPosition = self.data.gcodeShift[1] * self.canvasScaleFactor + if (self.data.units=="INCHES"): + scaleFactor = 1.0; + else: + scaleFactor = 1/25.4; + #before, gcode shift = home X + #old #self.xPosition = self.data.gcodeShift[0] * scaleFactor + #old #self.yPosition = self.data.gcodeShift[1] * scaleFactor + #self.xPosition = float(self.data.config.getValue("Advanced Settings", "homeX")) * scaleFactor #test123 + #self.yPosition = float(self.data.config.getValue("Advanced Settings", "homeY")) * scaleFactor #test123 + self.xPosition = 0 + self.yPosition = 0 self.zPosition = 0 self.prependString = "G00 " @@ -521,13 +840,26 @@ def updateGcode(self): errorText = ( "The current file contains " + str(len(self.data.gcode)) - + " lines of gcode.\nrendering all " + + " lines of gcode. Rendering all " + str(len(self.data.gcode)) - + " lines simultaneously may crash the\n program, only the first " - + self.maxNumberOfLinesToRead - + "lines are shown here.\nThe complete program will cut if you choose to do so unless the home position is moved from (0,0)." + + " lines simultaneously may crash the program, therefore, only the first " + + str(self.maxNumberOfLinesToRead) + + "lines are shown here. The complete program will cut if you choose to do so unless the home position is moved from (0,0)." ) - print(errorText) - self.data.ui_queue.put("Message: " + errorText) + self.data.console_queue.put(errorText) + self.data.ui_queue1.put("Alert", "Alert", errorText) + + + th = threading.Thread(target=self.callBackMechanism) + th.start() + + + def getLinePoints(self): - self.callBackMechanism(self.updateGcode) + points = [] + for line in self.line3D: + for point in line.points: + if point[2]<0: + newPoint = [point[0],point[1]] + points.append(newPoint) + return points diff --git a/File/importFile.py b/File/importFile.py index fb431345..33a0e7e1 100644 --- a/File/importFile.py +++ b/File/importFile.py @@ -1,14 +1,11 @@ from DataStructures.makesmithInitFuncs import MakesmithInitFuncs -import sys -import threading import re -import math - +import json class ImportFile(MakesmithInitFuncs): def importGCini(self, filename): - print(filename) + self.data.console_queue.put(filename) if filename is "": # Blank file? return False try: @@ -34,13 +31,78 @@ def importGCini(self, filename): else: if section != "": setting = [x.strip() for x in line.split("=")] - # print(section+"->"+setting[0]+":"+setting[1]) self.data.config.setValue( - section, setting[0], setting[1], True - ) # True to prevent recomputing settings everytime. + section, setting[0], setting[1], True, isImporting=True, + ) + self.data.console_queue.put("computing settings") self.data.config.computeSettings(None, None, None, True) + self.data.gcode_queue.put("$$") + except: + self.data.console_queue.put("Import File Error") + self.data.message_queue.put("Message: Cannot open import file.") + return False + return True + + def importWebControlJSON(self, filename): + self.data.console_queue.put(filename) + if filename is "": # Blank file? + return False + try: + with open(filename, "r") as infile: + imported = json.load(infile) + updated = False + for section in imported: + sectionFound = False + for x in range(len(imported[section])): + found = False + for _section in self.data.config.settings: + if _section == section: + sectionFound = True + for y in range(len(self.data.config.settings[_section])): + if imported[section][x]["key"] == self.data.config.settings[_section][y]["key"]: + found = True + if "value" in imported[section][x]: + if self.data.config.settings[_section][y]["value"] != imported[section][x]["value"]: + self.data.config.settings[_section][y]["value"] = imported[section][x]["value"] + self.data.console_queue.put("Updated "+self.data.config.settings[_section][y]["key"]) + updated = True + break + if not found: + if sectionFound: + print("section found") + else: + print("section not found") + self.data.config.settings[section] = [] + print(section + "->" + imported[section][x]["key"] + " was not found..") + t = {} + if "default" in imported[section][x]: + t["default"] = imported[section][x]["default"] + if "desc" in imported[section][x]: + t["desc"] = imported[section][x]["desc"] + if "firmwareKey" in imported[section][x]: + t["firmwareKey"] = imported[section][x]["firmwareKey"] + if "key" in imported[section][x]: + t["key"] = imported[section][x]["key"] + if "section" in imported[section][x]: + t["section"] = imported[section][x]["section"] + if "title" in imported[section][x]: + t["title"] = imported[section][x]["title"] + if "type" in imported[section][x]: + t["type"] = imported[section][x]["type"] + if "value" in imported[section][x]: + t["value"] = imported[section][x]["value"] + if "options" in imported[section][x]: + t["options"] = imported[section][x]["options"] + self.data.config.settings[section].append(t) + print("added " + section + "->" + self.data.config.settings[section][len(self.data.config.settings[section]) - 1]["key"]) + updated = True + if updated: + with open(self.data.config.home+"/.WebControl/webcontrol.json", "w") as outfile: + json.dump(self.data.config.settings, outfile, sort_keys=True, indent=4, ensure_ascii=False) + self.data.gcode_queue.put("$$") except: - print("Import File Error") + self.data.console_queue.put("Import File Error") self.data.message_queue.put("Message: Cannot open import file.") return False return True + diff --git a/static/scripts/gcode.js b/GCodeOptimizer/__init__.py similarity index 100% rename from static/scripts/gcode.js rename to GCodeOptimizer/__init__.py diff --git a/GCodeOptimizer/gcodeOptimizer.py b/GCodeOptimizer/gcodeOptimizer.py new file mode 100644 index 00000000..5faf6799 --- /dev/null +++ b/GCodeOptimizer/gcodeOptimizer.py @@ -0,0 +1,347 @@ +from __future__ import print_function +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs +import re +import math +from ortools.constraint_solver import routing_enums_pb2 +from ortools.constraint_solver import pywrapcp + + + + +def print_solution(manager, routing, solution): + """Prints solution on console.""" + print('Objective: {} miles'.format(solution.ObjectiveValue())) + index = routing.Start(0) + plan_output = 'Route for vehicle 0:\n' + route_distance = 0 + while not routing.IsEnd(index): + plan_output += ' {} ->'.format(manager.IndexToNode(index)) + previous_index = index + index = solution.Value(routing.NextVar(index)) + route_distance += routing.GetArcCostForVehicle(previous_index, index, 0) + plan_output += ' {}\n'.format(manager.IndexToNode(index)) + print(plan_output) + plan_output += 'Route distance: {}miles\n'.format(route_distance) + + +# The idea for this class is to minimize the distance of G0 moves (i.e., moves above z-axis of 0.0) +# GCode optimization is not a straight travelling salesperson problem (TSP) because their are distinct start and stop +# coordinates involved. In a TSP problem, optimizers just minimize the total travel time between discrete locations +# (i.e., cities). This method would work well if all gcode was drill operations. However, because each line has a +# start and stop, it doesn't apply. This is more of a Taxi Cab Problem (TCP) where a taxi driver has a list +# of pickups and dropoffs and wants to optimize his route to minimize the travel time. Whearas in the TSP, the +# "pickup" and 'dropoff" location is the same, in the TCP, they are different. +# +# The problems associated with optimizing gcode are: +# 1. Use of relative positioning will be challenging. Solution might be to disallow in optimization +# 2. + +# https://github.com/ezstoltz/genetic-algorithm/blob/master/genetic_algorithm_TSP.ipynb + +class Path: + x0 = 0 # beginning x,y of the gcode group + y0 = 0 + x1 = 0 # end x,y of the gcode group + y1 = 0 + startLine = 0 # index of first gcode line of gcode group in gcode file + finishLine = 0 # index of last gcode line of gcode group in gcode file + tool = 0 + + def __init__(self, x0, y0, x1, y1, startLine, finishLine, tool): + if x0 is not None: + self.x0 = float(x0) + else: + self.x0 = None + if y0 is not None: + self.y0 = float(y0) + else: + self.y0 = None + if x1 is not None: + self.x1 = float(x1) + else: + self.x1 = None + if y1 is not None: + self.y1 = float(y1) + else: + self.y1 = None + self.startLine = startLine + self.finishLine = finishLine + self.tool = tool + print(self) + + def __repr__(self): + return "[("+str(self.x0)+","+str(self.y0)+")-("+str(self.x1)+","+str(self.y1)+") ("+str(self.startLine)+":"+str(self.finishLine)+") ("+str(self.tool)+")]" + + +def getXYFromGCode(gCodeLine, xTarget, yTarget): + gCodeLine = gCodeLine.upper() + " " + x = re.search("X(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + if x: + xTarget = float(x.groups()[0]) + y = re.search("Y(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + if y: + yTarget = float(y.groups()[0]) + + return xTarget, yTarget + +def getZFromGCode(gCodeLine): + gCodeLine = gCodeLine.upper() + " " + zTarget = None + z = re.search("Z(?=.)(([ ]*)?[+-]?([0-9]*)(\.([0-9]+))?)", gCodeLine) + if z: + zTarget = float(z.groups()[0]) + return zTarget + +def isComment(line): + comment1 = line.find("(") + comment2 = line.find(";") + if comment1 == 0 or comment2 == 0: + return True + return False + +def stripComments(line): + comment1 = line.find("(") + if comment1 != -1: + line = line[:comment1] + comment1 = line.find(";") + if comment1 != -1: + line = line[:comment1] + line = (line + " ") + return line + +def findInLine(line, code, len): + gPos = line.find(code) + gString = line[line.find(code): line.find(code) + len] + return gString + +def getNumberAfterCode(line, code): + cPos = line.find(code) + number = line[cPos+1:] # slice off the T + return number + +class GCodeOptimizer(MakesmithInitFuncs): + + def __init__(self): + # can't do much because data hasn't been initialized yet + pass + + def optimize(self): + # find max z: + maxZTarget = 0 + units = None + for line in self.data.gcode: + line = stripComments(line) + gString = line[line.find("G"): line.find("G") + 3] + if gString == "G21": + if units is not None and units != "G21": + print("Error, units switch in file") + return False + units = "G21" + if gString == "G20": + if units is not None and units != "G20": + print("Error, units switch in file") + return False + units = "G20" + if gString == "G00" or gString == "G0 ": #found G0/G00 + zTarget = getZFromGCode(line) + if zTarget is not None: + if float(zTarget) > float(maxZTarget): + maxZTarget = zTarget + pathList = [] + inPath = False + index = 0 + startLine = 0 + startX = None + startY = None + currentX = None + currentY = None + inHeader = True + headerEnd = 0 + tool = 0 + toolList = [0] + footerStart = 0 + #path list will hold the parsed gcode groups between G0 moves. + for line in self.data.gcode: + line = stripComments(line) + tString = findInLine(line, "T", 2) # search for tool command + if len(tString) > 1: + toolVal = getNumberAfterCode(line, "T") + toolVal = int(toolVal) + print(line) + print(toolVal) + if toolVal != tool: + if inPath: #close off current path + endX = currentX + endY = currentY + pathList.append( + Path(x0=startX, y0=startY, x1=endX, y1=endY, startLine=startLine, finishLine=index, tool=tool)) + #currentX, currentY = getXYFromGCode(line, currentX, currentY) #there won't be a currentX, currentY in this code + inPath = False + toolList.append(toolVal) + tool = toolVal + print("Current tool is now: "+str(tool)) + gString = findInLine(line, "G", 3) + if True: + if gString == "G00" or gString == "G0 ": #found G0/G00 + if not inPath: + if currentX is None and currentY is None: + startX, startY = getXYFromGCode(line, currentX, currentY) + currentX = startX + currentY = startY + inHeader = False + else: + startX = currentX + startY = currentY + endX, endY = getXYFromGCode(line, currentX, currentY) + currentX = endX + currentY = endY + inHeader = False + else: + endX = currentX + endY = currentY + pathList.append(Path(x0=startX, y0=startY, x1=endX,y1=endY, startLine=startLine, finishLine=index, tool=tool)) + currentX, currentY = getXYFromGCode(line, currentX, currentY) + inPath = False + + elif gString == "G01" or gString == "G1 " or gString == "G02" or gString == "G2 " or gString == "G03" or gString == "G3 ": #found G1/G01/G2/G02/G3/G03 + endX, endY = getXYFromGCode(line, currentX, currentY) + if startX is None or startY is None: + headerEnd = index + else: + if not inPath: + startLine = index + startX = currentX + startY = currentY + if endX is None: + endX = startX + if endY is None: + endY = startY + currentX = endX + currentY = endY + inPath = True + inHeader = False + else: + if inHeader: + headerEnd = index + #print(line) + #print(str(inPath)+"=>"+ str(startX) + ", " + str(startY)+" - "+str(currentX) + ", " + str(currentY)) + index = index + 1 + + #print("last"+str(inPath)+"=>"+ str(startX) + ", " + str(startY)+" - "+str(currentX) + ", " + str(currentY)) + + newGCode = [] + newGCode.append(units) + for i in range(0, headerEnd+1): + line = self.data.gcode[i] + gString = line[line.find("G"): line.find("G") + 3] + if gString != "G21" and gString != "G20": # don't setup units anymore + newGCode.append(self.data.gcode[i]) + + #repeat for each tool: + print("ToolList") + print(toolList) + for tool in toolList: + """Entry point of the program.""" + # Instantiate the data problem. + newGCode.append("M6 T"+str(tool)) + data = create_data_model(pathList, tool) + if len(data['locations']) > 0: #could be nulled out because first tool is not 0 + manager = pywrapcp.RoutingIndexManager(len(data['locations']), data['num_vehicles'], data['depot']) + routing = pywrapcp.RoutingModel(manager) + distance_matrix = compute_euclidean_distance_matrix(data['locations']) + + def distance_callback(from_index, to_index): + """Returns the distance between the two nodes.""" + # Convert from routing variable Index to distance matrix NodeIndex. + from_node = manager.IndexToNode(from_index) + to_node = manager.IndexToNode(to_index) + return distance_matrix[from_node][to_node] + + transit_callback_index = routing.RegisterTransitCallback(distance_callback) + routing.SetArcCostEvaluatorOfAllVehicles(transit_callback_index) + search_parameters = pywrapcp.DefaultRoutingSearchParameters() + search_parameters.first_solution_strategy = ( + routing_enums_pb2.FirstSolutionStrategy.PATH_CHEAPEST_ARC) + solution = routing.SolveWithParameters(search_parameters) + if solution: + print_solution(manager, routing, solution) + + """Prints solution on console.""" + index = routing.Start(0) + route_distance = 0 + while not routing.IsEnd(index): + pathIndex = manager.IndexToNode(index) + startLine = data['locations'][pathIndex][4] + finishLine = data['locations'][pathIndex][5] + newGCode.append("G0 Z" + str(maxZTarget)) + newGCode.append("G0 X" + str(data['locations'][pathIndex][0]) + " Y" + str(data['locations'][pathIndex][1])) + line = self.data.gcode[startLine] + gString = line[line.find("G"): line.find("G") + 3] + if gString == "G01" or gString == "G1 ": # found G0/G00 + X, Y = getXYFromGCode(line, None, None) + if X is None and Y is None: + zTarget = getZFromGCode(line) + if float(zTarget) < 0: + newGCode.append("G0 Z0.5") + for i in range(startLine, finishLine): + newGCode.append(self.data.gcode[i]) + previous_index = index + index = solution.Value(routing.NextVar(index)) + route_distance += routing.GetArcCostForVehicle(previous_index, index, 0) + else: + print("No locations for tool"+str(tool)) + + newGCode.append("G0 Z" + str(maxZTarget)) + newGCode.append("G0 X" + str(currentX) + " Y" + str(currentY)) + + print('Objective: {} units\n'.format(solution.ObjectiveValue()/100)) + print('Path distance: {} units\n'.format(route_distance/100)) + + ''' + for path in bestRoute: + newGCode.append("G0 Z" + str(maxZTarget)) + newGCode.append("G0 X" + str(path.x0) + " Y" + str(path.y0)) + #print("G0 Z" + str(maxZTarget)) + #print("G0 X" + str(path.x0) + " Y" + str(path.y0)) + for i in range(path.startLine, path.finishLine ): + newGCode.append(self.data.gcode[i]) + #print(self.data.gcode[i]) + ''' + finalGCode = "" + for i in newGCode: + finalGCode = finalGCode + i + "\n" + self.data.actions.updateGCode(finalGCode) + + return True + + + + + + +def create_data_model(pathList, tool): + """Stores the data for the problem.""" + data = {} + data['locations'] = [] + # Locations in block units + for path in pathList: + if path.tool == tool: + data['locations'].append( (path.x0, path.y0, path.x1, path.y1, path.startLine, path.finishLine ) ) + data['num_vehicles'] = 1 + data['depot'] = 0 + return data + +def compute_euclidean_distance_matrix(locations): + """Creates callback to return distance between points.""" + distances = {} + for from_counter, from_node in enumerate(locations): + distances[from_counter] = {} + for to_counter, to_node in enumerate(locations): + if from_counter == to_counter: + distances[from_counter][to_counter] = 0 + else: + # Euclidean distance + distances[from_counter][to_counter] = (int(100* + math.hypot((from_node[2] - to_node[0]), + (from_node[3] - to_node[1])))) + return distances \ No newline at end of file diff --git a/GETTINGSTARTED b/GETTINGSTARTED new file mode 100644 index 00000000..387ce7df --- /dev/null +++ b/GETTINGSTARTED @@ -0,0 +1,59 @@ + +Link to image for installing on sd card: + +https://drive.google.com/file/d/132811KALMXDlxUa9jGZdCv1eB2lz09Ws/view?usp=sharing + +Suggestions on getting started: + +1. If you have ground control up and running and your machine is calibrated... +1.a. Go into ground control and set one of the macros to the following command: B09 L1650 R1650 (this assumes you have a 10 foot beam + and haven't changed the extend chain distance). Once assigned, press the respective macro button and the sled should move to what + I refer to as the 'default position'. This is the position the sled would be in after your set the sprockets to vertical and + extended the chains so you can attach the sled while you were calibrating the machine. +1.b. Copy your groundcontrol.ini file to the computer that you will be using to communicate with webcontrol. You'll be importing your + groundcontrol.ini file into webcontrol to ease the transition. + +2. Burn the iso to the sd card, add your wpa_supplicant/ssh files to boot, insert into RPI, power on and wait 3-5 minutes. + +3. Browse to http://xxx.xxx.xxx.xxx:5001, where "xxx.xxx.xxx.xxx" is the IP address of the RPI. This is WebMCP. + +4. Press "Start WebControl". You'll see a WebMCP message saying "Start WebControl" and after about 5 minutes or so (because it has to + download webcontrol) you'll see a message that says "Started WebControl: something_in_hex". After 10-15 seconds, you'll see watchdog + messages from WebControl.. probably something about "connecting.. is not available or in use.." That's basically saying that + webcontrol can't connect to the controller because the port is not configured yet. + +5. Browse to xxx.xxx.xxx.xxx:5000 and you should see a screen with a notice about being the first time run. + + +If you did step 1 (have a groundcontrol.ini file) do this: + +6. Click Actions and under "Calibration/Setup" click "import groundcontrol.ini file". Choose your groundcontrol.ini file and submit it. + If all goes well, the file will be imported and webcontrol will connect to the controller using the correct port. If it doesn't + connect, please let me know by posting an issue on github. You can manually set the port by going to Settings->Maslow Settings and + clicking the 'refresh' simple next to the port input to populate the list of found ports. Select the port and then scroll to bottom + and hit submit. + +If you didn't do step 1 (i.e., need to start from scratch) + +6. Click Actions and under "Calibration/Setup" click "Quick Configure". Then (and now that I think about this, I'll probably add this + to quick configure) go to Settings->Maslow Settings and to the right of the list box for Serial Connection, there's a refresh button. + Press it and list of ports will appear. On my RPi, the correct port is /dev/ttyACM0. + +If all goes well, you'll get connected and up and running and MAYBE an error about firmware being off.. though I don't think you will. +However, webcontrol expects a certain firmware that I've developed for optical calibration and though webcontrol works with stock +firmware (from what we can tell) you might see some spammy error messages from the controller regarding "Bad number value" or something +like that. That's the controller saying that it received a setting it doesn't understand. I'm looking to add in a way to avoid that +without breaking compatibility with ground control. + +However, if you decide you want to stick with using webcontrol, you can update the firmware to my custom version by clicking Actions +then "Upgrade Firmware". If you ever want to go back to the stock firmware, you need to use the arduino programmer and such. + +IF YOU GET A "CANNOT FIND POSITION FOR CHAIN LENGTHS X, X" MESSAGE: + +This is where we need some testing. Ideally, you should be able to go between ground control and webcontrol without any issues if the +settings are all synced properly. I *think* I've gotten it to that point, but I need other people to try out importing the +groundcontrol.ini file and see if they get the same results. If you got the message after importing groundcontrol.ini and you had moved +the sled to the default position using the macro, click "Clear" to clear the alarm and then go to Actions and click "Reset Chain +Lengths". It will tell the controller that its at the default position and I think things will work. + +Let me know what works, what doesn't work, and what's confusing. diff --git a/HelpManager/__init__.py b/HelpManager/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/HelpManager/helpManager.py b/HelpManager/helpManager.py new file mode 100644 index 00000000..21e9df34 --- /dev/null +++ b/HelpManager/helpManager.py @@ -0,0 +1,40 @@ +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs +import re +import requests +from github import Github +import hashlib +from base64 import b64decode +import base64 + +class HelpManager(MakesmithInitFuncs): + + def __init__(self): + pass + + repo = None + + def getReleases(self): + return self.releases + + def getLatestRelease(self): + return self.latestRelease + + def checkForUpdatedHelp(self): + pages = self.getHelpPages() + print(pages) + return True + + def getHelpPages(self): + return None + g = Github() + self.repo = g.get_repo("madgrizzle/WebControl") + contents = self.repo.get_contents("docs") + pages = [] + while contents: + file_content = contents.pop(0) + if file_content.type == "dir": + contents.extend(self.repo.get_contents(file_content.path)) + else: + pages.append({"name": file_content.name, "download_url": file_content.download_url}) + return pages + diff --git a/LICENSE b/LICENSE new file mode 100644 index 00000000..ff50514e --- /dev/null +++ b/LICENSE @@ -0,0 +1,189 @@ +GNU GENERAL PUBLIC LICENSE + +Version 3, 29 June 2007 + +Copyright © 2007 Free Software Foundation, Inc. + +Everyone is permitted to copy and distribute verbatim copies of this license document, but changing it is not allowed. +Preamble + +The GNU General Public License is a free, copyleft license for software and other kinds of works. + +The licenses for most software and other practical works are designed to take away your freedom to share and change the works. By contrast, the GNU General Public License is intended to guarantee your freedom to share and change all versions of a program--to make sure it remains free software for all its users. We, the Free Software Foundation, use the GNU General Public License for most of our software; it applies also to any other work released this way by its authors. You can apply it to your programs, too. + +When we speak of free software, we are referring to freedom, not price. Our General Public Licenses are designed to make sure that you have the freedom to distribute copies of free software (and charge for them if you wish), that you receive source code or can get it if you want it, that you can change the software or use pieces of it in new free programs, and that you know you can do these things. + +To protect your rights, we need to prevent others from denying you these rights or asking you to surrender the rights. Therefore, you have certain responsibilities if you distribute copies of the software, or if you modify it: responsibilities to respect the freedom of others. + +For example, if you distribute copies of such a program, whether gratis or for a fee, you must pass on to the recipients the same freedoms that you received. You must make sure that they, too, receive or can get the source code. And you must show them these terms so they know their rights. + +Developers that use the GNU GPL protect your rights with two steps: (1) assert copyright on the software, and (2) offer you this License giving you legal permission to copy, distribute and/or modify it. + +For the developers' and authors' protection, the GPL clearly explains that there is no warranty for this free software. For both users' and authors' sake, the GPL requires that modified versions be marked as changed, so that their problems will not be attributed erroneously to authors of previous versions. + +Some devices are designed to deny users access to install or run modified versions of the software inside them, although the manufacturer can do so. This is fundamentally incompatible with the aim of protecting users' freedom to change the software. The systematic pattern of such abuse occurs in the area of products for individuals to use, which is precisely where it is most unacceptable. Therefore, we have designed this version of the GPL to prohibit the practice for those products. If such problems arise substantially in other domains, we stand ready to extend this provision to those domains in future versions of the GPL, as needed to protect the freedom of users. + +Finally, every program is threatened constantly by software patents. States should not allow patents to restrict development and use of software on general-purpose computers, but in those that do, we wish to avoid the special danger that patents applied to a free program could make it effectively proprietary. To prevent this, the GPL assures that patents cannot be used to render the program non-free. + +The precise terms and conditions for copying, distribution and modification follow. +TERMS AND CONDITIONS +0. Definitions. + +“This License” refers to version 3 of the GNU General Public License. + +“Copyright” also means copyright-like laws that apply to other kinds of works, such as semiconductor masks. + +“The Program” refers to any copyrightable work licensed under this License. Each licensee is addressed as “you”. “Licensees” and “recipients” may be individuals or organizations. + +To “modify” a work means to copy from or adapt all or part of the work in a fashion requiring copyright permission, other than the making of an exact copy. The resulting work is called a “modified version” of the earlier work or a work “based on” the earlier work. + +A “covered work” means either the unmodified Program or a work based on the Program. + +To “propagate” a work means to do anything with it that, without permission, would make you directly or secondarily liable for infringement under applicable copyright law, except executing it on a computer or modifying a private copy. Propagation includes copying, distribution (with or without modification), making available to the public, and in some countries other activities as well. + +To “convey” a work means any kind of propagation that enables other parties to make or receive copies. Mere interaction with a user through a computer network, with no transfer of a copy, is not conveying. + +An interactive user interface displays “Appropriate Legal Notices” to the extent that it includes a convenient and prominently visible feature that (1) displays an appropriate copyright notice, and (2) tells the user that there is no warranty for the work (except to the extent that warranties are provided), that licensees may convey the work under this License, and how to view a copy of this License. If the interface presents a list of user commands or options, such as a menu, a prominent item in the list meets this criterion. +1. Source Code. + +The “source code” for a work means the preferred form of the work for making modifications to it. “Object code” means any non-source form of a work. + +A “Standard Interface” means an interface that either is an official standard defined by a recognized standards body, or, in the case of interfaces specified for a particular programming language, one that is widely used among developers working in that language. + +The “System Libraries” of an executable work include anything, other than the work as a whole, that (a) is included in the normal form of packaging a Major Component, but which is not part of that Major Component, and (b) serves only to enable use of the work with that Major Component, or to implement a Standard Interface for which an implementation is available to the public in source code form. A “Major Component”, in this context, means a major essential component (kernel, window system, and so on) of the specific operating system (if any) on which the executable work runs, or a compiler used to produce the work, or an object code interpreter used to run it. + +The “Corresponding Source” for a work in object code form means all the source code needed to generate, install, and (for an executable work) run the object code and to modify the work, including scripts to control those activities. However, it does not include the work's System Libraries, or general-purpose tools or generally available free programs which are used unmodified in performing those activities but which are not part of the work. For example, Corresponding Source includes interface definition files associated with source files for the work, and the source code for shared libraries and dynamically linked subprograms that the work is specifically designed to require, such as by intimate data communication or control flow between those subprograms and other parts of the work. + +The Corresponding Source need not include anything that users can regenerate automatically from other parts of the Corresponding Source. + +The Corresponding Source for a work in source code form is that same work. +2. Basic Permissions. + +All rights granted under this License are granted for the term of copyright on the Program, and are irrevocable provided the stated conditions are met. This License explicitly affirms your unlimited permission to run the unmodified Program. The output from running a covered work is covered by this License only if the output, given its content, constitutes a covered work. This License acknowledges your rights of fair use or other equivalent, as provided by copyright law. + +You may make, run and propagate covered works that you do not convey, without conditions so long as your license otherwise remains in force. You may convey covered works to others for the sole purpose of having them make modifications exclusively for you, or provide you with facilities for running those works, provided that you comply with the terms of this License in conveying all material for which you do not control copyright. Those thus making or running the covered works for you must do so exclusively on your behalf, under your direction and control, on terms that prohibit them from making any copies of your copyrighted material outside their relationship with you. + +Conveying under any other circumstances is permitted solely under the conditions stated below. Sublicensing is not allowed; section 10 makes it unnecessary. +3. Protecting Users' Legal Rights From Anti-Circumvention Law. + +No covered work shall be deemed part of an effective technological measure under any applicable law fulfilling obligations under article 11 of the WIPO copyright treaty adopted on 20 December 1996, or similar laws prohibiting or restricting circumvention of such measures. + +When you convey a covered work, you waive any legal power to forbid circumvention of technological measures to the extent such circumvention is effected by exercising rights under this License with respect to the covered work, and you disclaim any intention to limit operation or modification of the work as a means of enforcing, against the work's users, your or third parties' legal rights to forbid circumvention of technological measures. +4. Conveying Verbatim Copies. + +You may convey verbatim copies of the Program's source code as you receive it, in any medium, provided that you conspicuously and appropriately publish on each copy an appropriate copyright notice; keep intact all notices stating that this License and any non-permissive terms added in accord with section 7 apply to the code; keep intact all notices of the absence of any warranty; and give all recipients a copy of this License along with the Program. + +You may charge any price or no price for each copy that you convey, and you may offer support or warranty protection for a fee. +5. Conveying Modified Source Versions. + +You may convey a work based on the Program, or the modifications to produce it from the Program, in the form of source code under the terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified it, and giving a relevant date. + b) The work must carry prominent notices stating that it is released under this License and any conditions added under section 7. This requirement modifies the requirement in section 4 to “keep intact all notices”. + c) You must license the entire work, as a whole, under this License to anyone who comes into possession of a copy. This License will therefore apply, along with any applicable section 7 additional terms, to the whole of the work, and all its parts, regardless of how they are packaged. This License gives no permission to license the work in any other way, but it does not invalidate such permission if you have separately received it. + d) If the work has interactive user interfaces, each must display Appropriate Legal Notices; however, if the Program has interactive interfaces that do not display Appropriate Legal Notices, your work need not make them do so. + +A compilation of a covered work with other separate and independent works, which are not by their nature extensions of the covered work, and which are not combined with it such as to form a larger program, in or on a volume of a storage or distribution medium, is called an “aggregate” if the compilation and its resulting copyright are not used to limit the access or legal rights of the compilation's users beyond what the individual works permit. Inclusion of a covered work in an aggregate does not cause this License to apply to the other parts of the aggregate. +6. Conveying Non-Source Forms. + +You may convey a covered work in object code form under the terms of sections 4 and 5, provided that you also convey the machine-readable Corresponding Source under the terms of this License, in one of these ways: + + a) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by the Corresponding Source fixed on a durable physical medium customarily used for software interchange. + b) Convey the object code in, or embodied in, a physical product (including a physical distribution medium), accompanied by a written offer, valid for at least three years and valid for as long as you offer spare parts or customer support for that product model, to give anyone who possesses the object code either (1) a copy of the Corresponding Source for all the software in the product that is covered by this License, on a durable physical medium customarily used for software interchange, for a price no more than your reasonable cost of physically performing this conveying of source, or (2) access to copy the Corresponding Source from a network server at no charge. + c) Convey individual copies of the object code with a copy of the written offer to provide the Corresponding Source. This alternative is allowed only occasionally and noncommercially, and only if you received the object code with such an offer, in accord with subsection 6b. + d) Convey the object code by offering access from a designated place (gratis or for a charge), and offer equivalent access to the Corresponding Source in the same way through the same place at no further charge. You need not require recipients to copy the Corresponding Source along with the object code. If the place to copy the object code is a network server, the Corresponding Source may be on a different server (operated by you or a third party) that supports equivalent copying facilities, provided you maintain clear directions next to the object code saying where to find the Corresponding Source. Regardless of what server hosts the Corresponding Source, you remain obligated to ensure that it is available for as long as needed to satisfy these requirements. + e) Convey the object code using peer-to-peer transmission, provided you inform other peers where the object code and Corresponding Source of the work are being offered to the general public at no charge under subsection 6d. + +A separable portion of the object code, whose source code is excluded from the Corresponding Source as a System Library, need not be included in conveying the object code work. + +A “User Product” is either (1) a “consumer product”, which means any tangible personal property which is normally used for personal, family, or household purposes, or (2) anything designed or sold for incorporation into a dwelling. In determining whether a product is a consumer product, doubtful cases shall be resolved in favor of coverage. For a particular product received by a particular user, “normally used” refers to a typical or common use of that class of product, regardless of the status of the particular user or of the way in which the particular user actually uses, or expects or is expected to use, the product. A product is a consumer product regardless of whether the product has substantial commercial, industrial or non-consumer uses, unless such uses represent the only significant mode of use of the product. + +“Installation Information” for a User Product means any methods, procedures, authorization keys, or other information required to install and execute modified versions of a covered work in that User Product from a modified version of its Corresponding Source. The information must suffice to ensure that the continued functioning of the modified object code is in no case prevented or interfered with solely because modification has been made. + +If you convey an object code work under this section in, or with, or specifically for use in, a User Product, and the conveying occurs as part of a transaction in which the right of possession and use of the User Product is transferred to the recipient in perpetuity or for a fixed term (regardless of how the transaction is characterized), the Corresponding Source conveyed under this section must be accompanied by the Installation Information. But this requirement does not apply if neither you nor any third party retains the ability to install modified object code on the User Product (for example, the work has been installed in ROM). + +The requirement to provide Installation Information does not include a requirement to continue to provide support service, warranty, or updates for a work that has been modified or installed by the recipient, or for the User Product in which it has been modified or installed. Access to a network may be denied when the modification itself materially and adversely affects the operation of the network or violates the rules and protocols for communication across the network. + +Corresponding Source conveyed, and Installation Information provided, in accord with this section must be in a format that is publicly documented (and with an implementation available to the public in source code form), and must require no special password or key for unpacking, reading or copying. +7. Additional Terms. + +“Additional permissions” are terms that supplement the terms of this License by making exceptions from one or more of its conditions. Additional permissions that are applicable to the entire Program shall be treated as though they were included in this License, to the extent that they are valid under applicable law. If additional permissions apply only to part of the Program, that part may be used separately under those permissions, but the entire Program remains governed by this License without regard to the additional permissions. + +When you convey a copy of a covered work, you may at your option remove any additional permissions from that copy, or from any part of it. (Additional permissions may be written to require their own removal in certain cases when you modify the work.) You may place additional permissions on material, added by you to a covered work, for which you have or can give appropriate copyright permission. + +Notwithstanding any other provision of this License, for material you add to a covered work, you may (if authorized by the copyright holders of that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the terms of sections 15 and 16 of this License; or + b) Requiring preservation of specified reasonable legal notices or author attributions in that material or in the Appropriate Legal Notices displayed by works containing it; or + c) Prohibiting misrepresentation of the origin of that material, or requiring that modified versions of such material be marked in reasonable ways as different from the original version; or + d) Limiting the use for publicity purposes of names of licensors or authors of the material; or + e) Declining to grant rights under trademark law for use of some trade names, trademarks, or service marks; or + f) Requiring indemnification of licensors and authors of that material by anyone who conveys the material (or modified versions of it) with contractual assumptions of liability to the recipient, for any liability that these contractual assumptions directly impose on those licensors and authors. + +All other non-permissive additional terms are considered “further restrictions” within the meaning of section 10. If the Program as you received it, or any part of it, contains a notice stating that it is governed by this License along with a term that is a further restriction, you may remove that term. If a license document contains a further restriction but permits relicensing or conveying under this License, you may add to a covered work material governed by the terms of that license document, provided that the further restriction does not survive such relicensing or conveying. + +If you add terms to a covered work in accord with this section, you must place, in the relevant source files, a statement of the additional terms that apply to those files, or a notice indicating where to find the applicable terms. + +Additional terms, permissive or non-permissive, may be stated in the form of a separately written license, or stated as exceptions; the above requirements apply either way. +8. Termination. + +You may not propagate or modify a covered work except as expressly provided under this License. Any attempt otherwise to propagate or modify it is void, and will automatically terminate your rights under this License (including any patent licenses granted under the third paragraph of section 11). + +However, if you cease all violation of this License, then your license from a particular copyright holder is reinstated (a) provisionally, unless and until the copyright holder explicitly and finally terminates your license, and (b) permanently, if the copyright holder fails to notify you of the violation by some reasonable means prior to 60 days after the cessation. + +Moreover, your license from a particular copyright holder is reinstated permanently if the copyright holder notifies you of the violation by some reasonable means, this is the first time you have received notice of violation of this License (for any work) from that copyright holder, and you cure the violation prior to 30 days after your receipt of the notice. + +Termination of your rights under this section does not terminate the licenses of parties who have received copies or rights from you under this License. If your rights have been terminated and not permanently reinstated, you do not qualify to receive new licenses for the same material under section 10. +9. Acceptance Not Required for Having Copies. + +You are not required to accept this License in order to receive or run a copy of the Program. Ancillary propagation of a covered work occurring solely as a consequence of using peer-to-peer transmission to receive a copy likewise does not require acceptance. However, nothing other than this License grants you permission to propagate or modify any covered work. These actions infringe copyright if you do not accept this License. Therefore, by modifying or propagating a covered work, you indicate your acceptance of this License to do so. +10. Automatic Licensing of Downstream Recipients. + +Each time you convey a covered work, the recipient automatically receives a license from the original licensors, to run, modify and propagate that work, subject to this License. You are not responsible for enforcing compliance by third parties with this License. + +An “entity transaction” is a transaction transferring control of an organization, or substantially all assets of one, or subdividing an organization, or merging organizations. If propagation of a covered work results from an entity transaction, each party to that transaction who receives a copy of the work also receives whatever licenses to the work the party's predecessor in interest had or could give under the previous paragraph, plus a right to possession of the Corresponding Source of the work from the predecessor in interest, if the predecessor has it or can get it with reasonable efforts. + +You may not impose any further restrictions on the exercise of the rights granted or affirmed under this License. For example, you may not impose a license fee, royalty, or other charge for exercise of rights granted under this License, and you may not initiate litigation (including a cross-claim or counterclaim in a lawsuit) alleging that any patent claim is infringed by making, using, selling, offering for sale, or importing the Program or any portion of it. +11. Patents. + +A “contributor” is a copyright holder who authorizes use under this License of the Program or a work on which the Program is based. The work thus licensed is called the contributor's “contributor version”. + +A contributor's “essential patent claims” are all patent claims owned or controlled by the contributor, whether already acquired or hereafter acquired, that would be infringed by some manner, permitted by this License, of making, using, or selling its contributor version, but do not include claims that would be infringed only as a consequence of further modification of the contributor version. For purposes of this definition, “control” includes the right to grant patent sublicenses in a manner consistent with the requirements of this License. + +Each contributor grants you a non-exclusive, worldwide, royalty-free patent license under the contributor's essential patent claims, to make, use, sell, offer for sale, import and otherwise run, modify and propagate the contents of its contributor version. + +In the following three paragraphs, a “patent license” is any express agreement or commitment, however denominated, not to enforce a patent (such as an express permission to practice a patent or covenant not to sue for patent infringement). To “grant” such a patent license to a party means to make such an agreement or commitment not to enforce a patent against the party. + +If you convey a covered work, knowingly relying on a patent license, and the Corresponding Source of the work is not available for anyone to copy, free of charge and under the terms of this License, through a publicly available network server or other readily accessible means, then you must either (1) cause the Corresponding Source to be so available, or (2) arrange to deprive yourself of the benefit of the patent license for this particular work, or (3) arrange, in a manner consistent with the requirements of this License, to extend the patent license to downstream recipients. “Knowingly relying” means you have actual knowledge that, but for the patent license, your conveying the covered work in a country, or your recipient's use of the covered work in a country, would infringe one or more identifiable patents in that country that you have reason to believe are valid. + +If, pursuant to or in connection with a single transaction or arrangement, you convey, or propagate by procuring conveyance of, a covered work, and grant a patent license to some of the parties receiving the covered work authorizing them to use, propagate, modify or convey a specific copy of the covered work, then the patent license you grant is automatically extended to all recipients of the covered work and works based on it. + +A patent license is “discriminatory” if it does not include within the scope of its coverage, prohibits the exercise of, or is conditioned on the non-exercise of one or more of the rights that are specifically granted under this License. You may not convey a covered work if you are a party to an arrangement with a third party that is in the business of distributing software, under which you make payment to the third party based on the extent of your activity of conveying the work, and under which the third party grants, to any of the parties who would receive the covered work from you, a discriminatory patent license (a) in connection with copies of the covered work conveyed by you (or copies made from those copies), or (b) primarily for and in connection with specific products or compilations that contain the covered work, unless you entered into that arrangement, or that patent license was granted, prior to 28 March 2007. + +Nothing in this License shall be construed as excluding or limiting any implied license or other defenses to infringement that may otherwise be available to you under applicable patent law. +12. No Surrender of Others' Freedom. + +If conditions are imposed on you (whether by court order, agreement or otherwise) that contradict the conditions of this License, they do not excuse you from the conditions of this License. If you cannot convey a covered work so as to satisfy simultaneously your obligations under this License and any other pertinent obligations, then as a consequence you may not convey it at all. For example, if you agree to terms that obligate you to collect a royalty for further conveying from those to whom you convey the Program, the only way you could satisfy both those terms and this License would be to refrain entirely from conveying the Program. +13. Use with the GNU Affero General Public License. + +Notwithstanding any other provision of this License, you have permission to link or combine any covered work with a work licensed under version 3 of the GNU Affero General Public License into a single combined work, and to convey the resulting work. The terms of this License will continue to apply to the part which is the covered work, but the special requirements of the GNU Affero General Public License, section 13, concerning interaction through a network will apply to the combination as such. +14. Revised Versions of this License. + +The Free Software Foundation may publish revised and/or new versions of the GNU General Public License from time to time. Such new versions will be similar in spirit to the present version, but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Program specifies that a certain numbered version of the GNU General Public License “or any later version” applies to it, you have the option of following the terms and conditions either of that numbered version or of any later version published by the Free Software Foundation. If the Program does not specify a version number of the GNU General Public License, you may choose any version ever published by the Free Software Foundation. + +If the Program specifies that a proxy can decide which future versions of the GNU General Public License can be used, that proxy's public statement of acceptance of a version permanently authorizes you to choose that version for the Program. + +Later license versions may give you additional or different permissions. However, no additional obligations are imposed on any author or copyright holder as a result of your choosing to follow a later version. +15. Disclaimer of Warranty. + +THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM “AS IS” WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. +16. Limitation of Liability. + +IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. +17. Interpretation of Sections 15 and 16. + +If the disclaimer of warranty and limitation of liability provided above cannot be given local legal effect according to their terms, reviewing courts shall apply local law that most closely approximates an absolute waiver of all civil liability in connection with the Program, unless a warranty or assumption of liability accompanies a copy of the Program in return for a fee. + +END OF TERMS AND CONDITIONS diff --git a/README.md b/README.md index c31aa35d..b0aadf83 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,167 @@ # WebControl -A web-based version of [MaslowCNC/GroundControl](https://www.github.com/MaslowCNC/GroundControl) +WebControl is a browser-based implementation of [MaslowCNC/GroundControl](https://github.com/MaslowCNC/GroundControl) for controlling a Maslow CNC. Ground Control utilizes Kivy as the graphic front end, which makes it difficult to implement multiple and/or remote access. WebControl, however, runs completely as a flask-socketio web server and inherently supports remote access and multiple screens. Therefore, WebControl can be installed on a low cost device like a Raspberry Pi, Windows 10, or linux (Debian) machines and the user can utilize their laptop, tablet and/or phone to control it.. all at the same time. Since the the installation supports headless operation, someone trying to build a self contained sled (i.e., motors located on the sled) can also install the Raspberry Pi on the sled as well. ![Screenshot](https://user-images.githubusercontent.com/218876/47197523-ac1d9e00-d31b-11e8-93c8-93a84a7eb0cf.png) +## Notice + +I'm having serious issues with building the docker files. Unless I can overcome those issues, there won't be any more docker updates. Therefore, I'm updating this section to put the pyinstall version usage up front... + +## Getting Started for Raspberry PI (Recommended Pyinstaller Release Instructions) + +For Windows 10 and Linux (Debian-based, such as Ubuntu) machines, users can download the latest single-file release, extract it, and run webcontrol. As a single-file release, it is completely portable and does not require an installation. The file unpacks itself into a temporary directory and runs. If you have a very slow computer, it might take a while to unpack. In that case, it is recommended to use the single-directory release which extracts into a single directory containing unpacked files. Startup is much quicker using single-directory releases versus a single-file release. For RPI, the single-file release is just way to slow, so I don't build it. + +**Note, for linux/RPI users, it will extract directly into the directory you are currently in.** + +For Linux/RPI users, make a new subdirectory,and then issue the untar: + +**For RPI:** +>cd ~
+>mkdir webcontrol
+>cd webcontrol
+>wget https://github.com/madgrizzle/WebControl/releases/download/v0.920/webcontrol-0.920-rpi-singledirectory.tar.gz
+>tar -zxvf webcontrol-0.920-rpi-singledirectory.tar.gz
+ +**For Linux:** +>cd ~
+>mkdir webcontrol
+>cd webcontrol
+>wget https://github.com/madgrizzle/WebControl/releases/download/v0.920/webcontrol-0.920-linux-singledirectory.tar.gz
+>tar -zxvf webcontrol-0.920-linux-singledirectory.tar.gz
+ +Change 0.920 to the lastest release if you want. + +For Windows users, just extract the zip file as is. + +Check out the release page at: + +https://github.com/madgrizzle/WebControl/releases + + +## Getting WebControl to Run Upon Startup on RPI (## NOT FULLY VETTED ##) + +Here's tentative instructions on how to get webcontrol to run on startup (from kayaker37 on forum).. This assumes you extracted webcontrol into a subdirectory called webcontrol: + +>nano webcontrol.service + +type the following: + +>[Unit]
+>Description=WebControl
+>After=network.target
+>
+>[Service]
+>ExecStart=/home/pi/webcontrol/webcontrol
+>WorkingDirectory=/home/pi/webcontrol
+>StandardOutput=inherit
+>StandardError=inherit
+>Restart=always
+>User=pi
+>
+>[Install]
+>WantedBy=multi-user.target
+ +Save file using Ctrl-X/Yes + +>sudo cp webcontrol.service /etc/systemd/system + +Test with the following: + +>sudo systemctl start webcontrol.service + +Try to reach webcontrol using your browser and if it works, then type: + +>sudo systemctl enable webcontrol.service + +see for more details: +https://www.raspberrypi.org/documentation/linux/usage/systemd.md + +## Getting Started for Raspberry Pi (Deprecated Docker.. Please do not use) + +These instructions are based upon using a Raspberry Pi (RPi) for running WebControl. WebControl should be able to be run on any computer capable of running Python 3. + +The simplest way to get started is to use the pre-built RPi image that @johnboiles has put together: + +https://drive.google.com/file/d/132811KALMXDlxUa9jGZdCv1eB2lz09Ws/view?usp=sharing 2 + +Download the file and burn it to your SD card. Add the appropriate ssh & wpa_supplicant.conf files for your network and then boot it. It will automatically download the latest WebMCP and start it (takes 3-5 minutes to complete the initial boot process). WebMCP is a watchdog/control program that allows you to start, stop, and update webcontrol. It also displays webcontrol messages that would normally print out in the terminal (like groundcontrol would do). WebMCP is bound to port 5001, so to reach it, open your browser and bring up http://xxx.xxx.xxx.xxx:5001 (where xxx... is your RPI's IP address). + +When WebMC comes up, click “Start WebControl” it will download the latest docker image and run it (takes another 3-5 minutes to docwnload). It may look like nothing is going on for a while, but just let it run. WebControl is bound to port 5000, so to reach it, browse to http://xxx.xxx.xxx.xxx:5000. + +Alternatively, you can install it onto an existing RPI OS by following these instructions. Note, the instructions assume your RPI has been configured with an IP address and SSH capability. + +### Prerequisites + +What things you need to install the software and how to install them + +* Maslow CNC +* Raspberry Pi configured for Internet access and SSH capability + +### Installing Docker onto Raspberry Pi + +WebControl can be installed by two different methods; either by downloading from github or from downloading the docker. Unless you are intending to perform development work on WebControl, we strongly recommend downloading the docker. Because of some of the libraries that are used for optical calibration, it can take hours to install from source. + +Log into your RPi via SSH and issue these commands: +``` +curl -fsSL get.docker.com -o get-docker.sh && sh get-docker.sh +sudo groupadd docker +sudo gpasswd -a $USER docker +newgrp docker +``` +These commands will download and install docker and create a docker group that allows you to run docker without using sudo. + +Test the installation of docker by issuing the following command: + +``` +docker run hello-world +``` + +### Installing WebMCP docker onto Raspberry Pi + +There are two ways to run WebControl. The first downloading and running the webcontrol docker and the second is by downloading and running WebMCP docker. WebMCP is "supervisor" program that can be used to start, stop and upgrade WebControl. The advantage if using WebMCP is that it provides a means to monitor and control WebControl from a browser. If WebControl seems non-responsive or something is amiss (it is still alpha-software), you can use WebMCP to see its health and stop/restart WebControl if needed. We have documentation (TBD) that describes how to start WebMCP upon boot of the RPi. Once configured, you won't need to SSH into the RPi to start/stop webcontrol. + +While logged into the RPi, issue the following command: +``` +docker pull madgrizzle/webmcp +docker run -it -v $HOME/.WebControl:/root/.WebControl -v /var/run/docker.sock:/var/run/docker.sock -p 5001:5001 -e HOST_HOME=$HOME --network=host --privileged madgrizzle/webmcp +``` + +### Setting Up WebMCP to Run on Boot + +You can configure WebMCP to start at boot using the example systemd unit file included in the [WebMCP repo](https://www.github.com/madgrizzle/WebMCP). + +``` +# TODO this line will eventually pull from madgrizzle/WebMCP directly when that repo is publicly available +sudo curl -fsSL https://gist.githubusercontent.com/johnboiles/da4f3fac73105c82d900e8118dae1ec4/raw/f5bf24641e7ce6c000b5d79dc0c5ed68477566f7/webmcp.service -o /etc/systemd/system/webmcp.service +sudo systemctl start webmcp +sudo systemctl enable webmcp +``` + +### Not Using WebMCP But Want To Run WebControl? + +So, if you don't want to use WebMCP, you can issue the following command to download the webcontrol docker and run it: + +``` +docker pull madgrizzle/webcontrol +docker run -it -v $HOME/.WebControl:/root/.WebControl -p 5000:5000 --privileged madgrizzle/webcontrol python main.py +``` + +## Built With + +* [Flask](http://flask.pocoo.org/) - The web framework used +* [Flask-Socketio](https://github.com/miguelgrinberg/Flask-SocketIO) - Websocket integration for communications with browser clients +* [Bootstrap4](https://getbootstrap.com/) - Front-end component library +* [Jinja2](http://jinja.pocoo.org/) - Template engine for web page generation +* [Feather.js](https://feathericons.com/) - Only icon library I could find that had diagonal arrows.. works well to boot. +* [OpenCV](https://github.com/skvark/opencv-python) - Library for computer vision to implement optical calibration +* [Numpy](http://www.numpy.org) - Library for math routines used with optical calibration +* [Scipy](http://www.scipy.org) - Another library for math routines used with optical calibration +* [Imutils](https://github.com/jrosebr1/imutils) - Adrian Rosebrock's library used with optical calibration +* [Schedule](https://github.com/dbader/schedule) - Library used to schedule checking connection with arduino +* [Ground Control](https://github.com/maslowcnc/groundcontrol) - Much of this was adapted from the Kivy-based Ground Control + + ## Developing ### Virtualenv @@ -17,6 +175,8 @@ You can use virtualenv to set up a local development environment for running the # Install the prerequisites pip install -r requirements.txt +When running on the Pi, you'll also need some extra dependencies and will need to build OpenCV from source. See the Dockerfile for details. (TODO: add instructions here) + Then you can run the code with. python main.py @@ -25,19 +185,19 @@ The server will then be available at http://localhost:5000 ### Docker -You can build a Docker image with +You can build a Docker image with (takes ~2-3 hours) docker build -t madgrizzle/webcontrol . Then you can run it directly - docker run -it -p 5000:5000 --privileged madgrizzle/webcontrol + docker run -it -p 5000:5000 -v $HOME/.WebControl:/root/.WebControl --privileged madgrizzle/webcontrol Or push it up to Docker Hub docker push madgrizzle/webcontrol -Note that the image can only be run from the same architecture it was built from. For example, an image built on an x86 laptop cannot be run on a RaspberryPi. +Note that you'll need to build the Docker image either on an ARM platform (e.g. RaspberryPi), or on a version of Docker that supports ARM emulation (either Docker for Mac or on Linux with binfmt_misc/qemu configured). ### Automatic code formatting @@ -60,3 +220,23 @@ If you don't have python3.6+ locally (to be able to run `black`), you can run `b With the [File Watchers](https://plugins.jetbrains.com/plugin/7177-file-watchers) and [BlackPycharm](https://plugins.jetbrains.com/plugin/10563-black-pycharm) plugins you can set up your editor to automatically format your code on save. Then you never have to think about code formatting again :tada: ![PyCharm Screenshot](https://user-images.githubusercontent.com/218876/47197011-817e1600-d318-11e8-8172-eb2c1ffe2d21.png) + +## Contributing + +Please read [CONTRIBUTING.md](https://gist.github.com/PurpleBooth/b24679402957c63ec426) for details on our code of conduct, and the process for submitting pull requests to us. + +## Versioning + +Added to TODO list? + +## Authors + +* **Madgrizzle** - *Initial work* - [madgrizzle](https://github.com/madgrizzle) +* **John Boiles** - *Docker Expert* - [johnboiles](https://github.com/johnboiles) +* **Tinker** - *UI Improvements/Bug Fixer/Etc.* - [gb0101010101](https://github.com/gb0101010101) + +See also the list of [contributors](https://github.com/your/project/contributors) who participated in this project. + +## License + +See [LICENSE](https://github.com/madgrizzle/WebControl/blob/master/LICENSE) diff --git a/ReleaseManager/__init__.py b/ReleaseManager/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/ReleaseManager/releaseManager.py b/ReleaseManager/releaseManager.py new file mode 100644 index 00000000..172918ec --- /dev/null +++ b/ReleaseManager/releaseManager.py @@ -0,0 +1,171 @@ +from DataStructures.makesmithInitFuncs import MakesmithInitFuncs +import time +import json +import datetime +import os +import glob +import zipfile +import re +from github import Github +import wget +import subprocess +from shutil import copyfile + + +class ReleaseManager(MakesmithInitFuncs): + + def __init__(self): + pass + + releases = None + latestRelease = None + + def getReleases(self): + tempReleases = [] + enableExperimental = self.data.config.getValue("WebControl Settings", "experimentalReleases") + for release in self.releases: + if not enableExperimental: + if not self.isExperimental(re.sub(r'[v]', r'', release.tag_name)): + tempReleases.append(release) + else: + tempReleases.append(release) + return tempReleases + + + def getLatestRelease(self): + return self.latestRelease + + def checkForLatestPyRelease(self): + if True: # self.data.platform=="PYINSTALLER": + print("Checking latest pyrelease.") + try: + enableExperimental = self.data.config.getValue("WebControl Settings", "experimentalReleases") + g = Github() + repo = g.get_repo("madgrizzle/WebControl") + self.releases = repo.get_releases() + latestVersionGithub = 0 + self.latestRelease = None + for release in self.releases: + tag_name = re.sub(r'[v]', r'', release.tag_name) + tag_float = float(tag_name) + eligible = False + if not enableExperimental: + if not self.isExperimental(tag_name): + eligible = True + else: + eligible = True + #print("tag:"+tag_name+", eligible:"+str(eligible)) + if eligible and tag_float > latestVersionGithub: + latestVersionGithub = tag_float + self.latestRelease = release + + print("Latest pyrelease: " + str(latestVersionGithub)) + if self.latestRelease is not None and latestVersionGithub > self.data.pyInstallCurrentVersion: + print("Latest release tag: " + self.latestRelease.tag_name) + assets = self.latestRelease.get_assets() + for asset in assets: + if asset.name.find(self.data.pyInstallType) != -1 and asset.name.find(self.data.pyInstallPlatform) != -1: + print(asset.name) + print(asset.url) + self.data.ui_queue1.put("Action", "pyinstallUpdate", "on") + self.data.pyInstallUpdateAvailable = True + self.data.pyInstallUpdateBrowserUrl = asset.browser_download_url + self.data.pyInstallUpdateVersion = self.latestRelease + except Exception as e: + print("Error checking pyrelease: " + str(e)) + + def isExperimental(self, tag): + ''' + Deternmines if release is experimental. All even releases are stable, odd releases are experimental + :param tag: + :return: + ''' + if float(tag) <= 0.931: # all releases before now are 'stable' + return False + lastDigit = tag[-1] + if (int(lastDigit) % 2) == 0: # only even releases are 'stable' + return False + else: + return True + + def processAbsolutePath(self, path): + index = path.find("main.py") + self.data.pyInstallInstalledPath = path[0:index - 1] + print(self.data.pyInstallInstalledPath) + + def updatePyInstaller(self, bypassCheck = False): + home = self.data.config.getHome() + if self.data.pyInstallUpdateAvailable == True or bypassCheck: + if not os.path.exists(home + "/.WebControl/downloads"): + print("creating downloads directory") + os.mkdir(home + "/.WebControl/downloads") + fileList = glob.glob(home + "/.WebControl/downloads/*.gz") + for filePath in fileList: + try: + os.remove(filePath) + except: + print("error cleaning download directory: ", filePath) + print("---") + if self.data.pyInstallPlatform == "win32" or self.data.pyInstallPlatform == "win64": + filename = wget.download(self.data.pyInstallUpdateBrowserUrl, out=home + "\\.WebControl\\downloads") + else: + filename = wget.download(self.data.pyInstallUpdateBrowserUrl, out=home + "/.WebControl/downloads") + print(filename) + + if self.data.platform == "PYINSTALLER": + lhome = os.path.join(self.data.platformHome) + else: + lhome = "." + if self.data.pyInstallPlatform == "win32" or self.data.pyInstallPlatform == "win64": + path = lhome + "/tools/upgrade_webcontrol_win.bat" + copyfile(path, home + "/.WebControl/downloads/upgrade_webcontrol_win.bat") + path = lhome + "/tools/7za.exe" + copyfile(path, home + "/.WebControl/downloads/7za.exe") + self.data.pyInstallInstalledPath = self.data.pyInstallInstalledPath.replace('/', '\\') + program_name = home + "\\.WebControl\\downloads\\upgrade_webcontrol_win.bat" + + else: + path = lhome + "/tools/upgrade_webcontrol.sh" + copyfile(path, home + "/.WebControl/downloads/upgrade_webcontrol.sh") + program_name = home + "/.WebControl/downloads/upgrade_webcontrol.sh" + self.make_executable(home + "/.WebControl/downloads/upgrade_webcontrol.sh") + tool_path = home + "\\.WebControl\\downloads\\7za.exe" + arguments = [filename, self.data.pyInstallInstalledPath, tool_path] + command = [program_name] + command.extend(arguments) + print("popening") + print(command) + subprocess.Popen(command) + return True + return False + + def make_executable(self, path): + print("1") + mode = os.stat(path).st_mode + print("2") + mode |= (mode & 0o444) >> 2 # copy R bits to X + print("3") + os.chmod(path, mode) + print("4") + + + def update(self, version): + ''' + Need to clean this up. + :param version: + :return: + ''' + for release in self.releases: + if release.tag_name == version: + assets = release.get_assets() + for asset in assets: + if asset.name.find(self.data.pyInstallType) != -1 and asset.name.find(self.data.pyInstallPlatform) != -1: + print(asset.name) + print(asset.url) + self.data.pyInstallUpdateBrowserUrl = asset.browser_download_url + print(self.data.pyInstallUpdateBrowserUrl) + return self.updatePyInstaller(True) + print("hmmm.. issue") + return False + + diff --git a/Services/MBrestart.sh b/Services/MBrestart.sh new file mode 100644 index 00000000..a2db26a5 --- /dev/null +++ b/Services/MBrestart.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl restart MaslowButton diff --git a/Services/MBstart.sh b/Services/MBstart.sh new file mode 100644 index 00000000..ecc9044d --- /dev/null +++ b/Services/MBstart.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl start MaslowButton diff --git a/Services/MBstop.sh b/Services/MBstop.sh new file mode 100644 index 00000000..cec1aaa5 --- /dev/null +++ b/Services/MBstop.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl stop MaslowButton diff --git a/Services/MPrestart.sh b/Services/MPrestart.sh new file mode 100644 index 00000000..f997fa04 --- /dev/null +++ b/Services/MPrestart.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl restart MaslowPendant diff --git a/Services/MPstart.sh b/Services/MPstart.sh new file mode 100644 index 00000000..02396166 --- /dev/null +++ b/Services/MPstart.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl start MaslowPendant diff --git a/Services/MPstop.sh b/Services/MPstop.sh new file mode 100644 index 00000000..fb3dfa0f --- /dev/null +++ b/Services/MPstop.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl stop MaslowPendant diff --git a/Services/MWCrestart.sh b/Services/MWCrestart.sh new file mode 100644 index 00000000..40878680 --- /dev/null +++ b/Services/MWCrestart.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl restart MaslowWC \ No newline at end of file diff --git a/Services/MWCstart.sh b/Services/MWCstart.sh new file mode 100644 index 00000000..7096be24 --- /dev/null +++ b/Services/MWCstart.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl start MaslowWC diff --git a/Services/MWCstop.sh b/Services/MWCstop.sh new file mode 100644 index 00000000..1bfaa403 --- /dev/null +++ b/Services/MWCstop.sh @@ -0,0 +1,3 @@ +#!/bin/bash + +sudo systemctl stop MaslowWC diff --git a/Services/MaslowButton.py b/Services/MaslowButton.py new file mode 100644 index 00000000..3010c629 --- /dev/null +++ b/Services/MaslowButton.py @@ -0,0 +1,321 @@ +#!/usr/bin/python3 +from gpiozero import Button +from gpiozero import LED +from signal import pause +import requests +import time +import subprocess +from subprocess import check_call +import json +import os +from os import system, name # import only system from os + +print("setting up buttons") +runpause = 0 +wiiPendantPresent = False +clidisplay = False +flag = '0' +Buttons = [] +LEDs = [] +index = 0 +moving = False +homeX = 0.00 +homeY = 0.00 +sledX = 0.00 +sledY = 0.00 +minX = 0.00 +minY = 0.00 +maxX = 0.00 +maxY = 0.00 +actionList = ["", "WebMCP Running", "Shutdown", "Stop", "Pause", "Play", "Home", "Return to Center", "PlayLED", "PauseLED", "StopLED"] +start_time = time.time() +end_time = time.time() +curtime = "none" +thetime = time.time() + +def timer(start,end): + hours, rem = divmod(end-start, 3600) + minutes, seconds = divmod(rem, 60) + return("{:0>2}:{:0>2}:{:05.2f}".format(int(hours),int(minutes),seconds)) + +def getpause(): + return runpause + +def setpause(newpause): + runpause = newpause + +def getActionList(self): + return actionList + +def Start(): + print ("start press") + Send("gcode:startRun") + print + +def Stop(): + print ("Stop press") + Send("gcode:stopRun") + +def getrunPause(): + return(runpause) + +def setrunPause(rp:int): + runpause = rp + print("set runpause to ", str(rp)) + +def runPause(): + rp = getrunPause() + print ("Pause press ", str(rp)) + if (rp == 0): + setrunPause(1) + Send("gcode:pauseRun") + else: + setrunPause(0) + Send("gcode:resumeRun") + +def returnHome(): + print ("return to center") + Send("gcode:home") + +def Exit(): + print ("EXIT") + #Send("system:exit") + os._exit(0) + +def Get(address,command): + try: + URL = "http://localhost:5000/" + str(address) + #print (URL) + r = requests.get(URL,params = command) + #print (r.text) + return r.json() + except: + print ('error getting data, check server') + return ('error:error') + +def Send(command): + try: + URL = "http://localhost:5000/GPIO" + r=requests.put(URL,command) + print (r) + except: + print ('error sending command, check server') + +def Shutdown(): + print ("shutting down system from button press") + check_call(['sudo', 'poweroff']) + +def startPendant(): + if (wiiPendantPresent): + print("kickstart pendant process (TOTALLY SEPARATE)") + try: + subprocess.run(['sudo','/usr/local/etc/MPstart.sh']) #MP is short for MaslowPendant + print ('subprocess started Pendant service') + except: + print ('error starting pendant sub process') + +def setup(): + #retdata = Get("GPIO", "GPIO") + URL = "http://localhost:5000/GPIO" + retdata = requests.get(URL,'GPIO') + setValues = retdata.json() + + #print(setValues) + for setting in setValues: + if setting["value"] != "": + pinNumber = int(setting["key"][4:]) + setGPIOAction(pinNumber, setting["value"]) + +def setGPIOAction(pin, action): + # first remove pin assignments if already made + foundButton = None + for button in Buttons: + if button.pin.number == pin: + button.pin.close() + foundButton = button + break + if foundButton is not None: + Buttons.remove(foundButton) + + foundLED = None + for led in LEDs: + if led[1].pin.number == pin: + led[1].pin.close() + foundLED = led + break + if foundLED is not None: + LEDs.remove(foundLED) + #print (LEDs) + + type, pinAction = getAction(action) + if type == "button": + button = Button(pin) + button.when_pressed = pinAction + Buttons.append(button) + print("set Button ", pin, " with action: ", action) + if type == "led": + _led = LED(pin) + led = (action,_led) + LEDs.append(led) + print("set LED with action: " + action) + #pause() + +def getAction(action): + #print(action) + if action == "Stop": + return "button", Stop + elif action == "Pause": + return "button", runPause + elif action == "Play": + return "button", Start + elif action == "Shutdown": + return "button", Shutdown + elif action == "Pendant": + return "button", startPendant + elif "Return" in action: + print("set return to center as button") + return "button", returnHome + else: + return "led", None + +def causeAction(action, onoff): + for led in LEDs: + if led[0] == action: + #print(led[1]) + if onoff == "on": + led[1].on() + elif onoff == "blink": + led[1].blink() + else: + led[1].off() + + #print(led[1]) + if action == "PlayLED" and onoff == "on": + causeAction("PauseLED", "off") + causeAction("StopLED", "off") + if action == "PauseLED" and onoff == "on": + causeAction("PlayLED", "on") + causeAction("StopLED", "off") + if action == "StopLED" and onoff == "on": + causeAction("PauseLED", "off") + causeAction("PlayLED", "off") +# define our clear function +def clear(): + # for windows + if name == 'nt': + _ = system('cls') + # for mac and linux(here, os.name is 'posix') + else: + _ = system('clear') + +def hms_string(sec_elapsed): + h = int(sec_elapsed / (60 * 60)) + m = int((sec_elapsed % (60 * 60)) / 60) + s = sec_elapsed % 60. + return "{}:{:>02}:{:>05.2f}".format(h, m, s) +# End hms_string + +#btnStart.when_pressed = Start +#btnPause.when_pressed = Pause +#btnStop.when_pressed = Stop +#btnExit.when_pressed = Shutdown +setup() + +bad_chars = "'" +#btnWiimote.when_pressed = Wii +print("waiting for button press") +#print (LEDs) +while True: + time.sleep (3) + try: + items = Get('LED','stuff') + if (items != None): + if (flag == "0"): + if(items["data"]["flag"] == "1"): + start_time = time.time() + else: + if(items["data"]["flag"] == "0"): + stop_time = time.time() + flag = items["data"]["flag"] + index = items["data"]["index"] + moving = items["data"]["moving"] + zMove = items["data"]["zMove"] + wiiPendantPresent = bool(items["data"]["wiiPendantPresent"]) + print ("wii pendant : ", wiiPendantPresent) + wiiconnected = bool(items["data"]["wiiconnected"]) + print ("wii connected : ", wiiconnected) + clidisplay = bool(items["data"]["clidisplay"]) + sledX = float(items["data"]["sled_location_X"]) + sledY = float(items["data"]["sled_location_y"]) + #"sled_location_z": str(app.data.zval), \ + homeX = float(items["data"]["home_location_x"]) + homeY = float(items["data"]["home_location_y"]) + xmin = float(items["data"]["gcode_min_x"]) + xmax = float(items["data"]["gcode_max_x"]) + ymin = float(items["data"]["gcode_min_y"]) + ymax = float(items["data"]["gcode_max_y"]) + #print (index) + #print (moving) + #print(items) + if (flag == 1): + RGC = True + pausedGcode = False + if (flag == 2): + pausedGcode = True + #if (index == '0'): + if (flag == '0'): # if 0, then stopped + print("stopped") + causeAction("StopLED", "on") + if (moving == 'True'): + print ("Moving") + causeAction("PlayLED", "blink") + if (moving == 'True'): + print ("zMove") + causeAction("PlayLED", "blink") + elif (flag == '1'): + print ("running") + causeAction("PlayLED", "on") + elif (flag == '2'): + print ("Paused") + causeAction("PauseLED", "on") + if (clidisplay == True): + clear() + print("") + if (flag == '1'): + end_time = time.time() + curtime = timer(start_time,end_time) + print(f"STATUS - run time: ", curtime) + print("") + else: + print("STATUS - not running") + print(f"last job: ", curtime) + if (wiiPendantPresent == True): + if (wiiconnected == True): + print("wiimote: attached") + else: + print("wiimote: disconnected") + print("") + print(f"Sled: {sledX:.2f},{sledY:.2f}") + print("") + print(f"Home: {homeX:.2f},{homeY:.2f}") + print("") + print("Bound box from sled (inches)") + upper = (ymax + sledY)/25.4 + right = (xmax + sledX)/25.4 + print(f"Top: {upper:.2f}") + print(f"Right: {right:.2f}") + print("Bound box from home (mm)") + upper = (ymax + homeY) + right = (xmax + homeX) + print("") + print(f"Top: {upper:.2f}") + print(f"Right: {right:.2f}") + print("") + print ("Absolute bounds") + print(f"Upper Right: {xmax:.2f}, {ymax:.2f}") + print(f"Lower Left: {xmin:.2f}, {ymin:.2f}") + #moving or other temp step, then mention? + except: + # pass + print ("error with display") + # fail in silence \ No newline at end of file diff --git a/Services/MaslowButton.service b/Services/MaslowButton.service new file mode 100644 index 00000000..072d1203 --- /dev/null +++ b/Services/MaslowButton.service @@ -0,0 +1,14 @@ +[Unit] +Description=Maslow Buttons daemon + +[Service] +Type=simple +ExecStart=/usr/bin/python3 /usr/local/etc/MaslowButton.py +WorkingDirectory=/usr/local/etc +StandardOutput=tty +TTYPath=/dev/tty1 +Restart=never +user=pi + +[Install] +WantedBy=sysinit.target diff --git a/Services/MaslowPendant.py b/Services/MaslowPendant.py new file mode 100644 index 00000000..4e7061d8 --- /dev/null +++ b/Services/MaslowPendant.py @@ -0,0 +1,303 @@ +#!/usr/bin/python +import requests +import cwiid +import time + +class WiiPendant(): + ''' + This class will connect to the wiimode with the Bluetooth address specified in the input file + This class relies on the setpoints in the /etc/cwiid/wminput/ folder of files that has the names of the input fields sent by the wiimote + 'BTN_1', 'BTN_2', 'BTN_A', 'BTN_B', 'BTN_DOWN', 'BTN_HOME', 'BTN_LEFT', 'BTN_MINUS', 'BTN_PLUS', 'BTN_RIGHT', 'BTN_UP', etc. + Commands (with wiimote readable) + move sled + UP: 1 + right + DOWN: 1 + left + LEFT: 1 + up + RIGHT: 1 + down + Home: HOME + move Z-Axis + UP: 2 + RIGHT + DOWN: 2 + LEFT + supervisory + Set HOME: 1 + HOME -> then A + Set Z axis zero: 2 + HOME -> then A + Disconnect wiimote: A + Z + PLAY: Z + RIGHT + PAUSE: Z + UP + RESUME: Z + DOWN + STOP: Z + LEFT + ''' + + def __init__(self): + ''' + init sets up the object properties that are used with the various functions below + A, trigger, ztrigger, confirm, home, a, b, all help with making the buttons single press + wm is the wiimote object + wiiPendantConnect is the flag that lets the class know to try and reconnect + ''' + self.L = [1,2,4,8] + self.DISTANCE = [0.1,1,10,100] + self.Z = [0.1, 0.5, 1, 5] + self.LED_ON = 2 # default is 10 mm. range is = 0.1, 1, 10, 100 Z_LED = 1 # default is 1 m. range is 0.1, 0.5, 1, 5 + self.MINUS = 0 + self.PLUS = 0 + self.TRIGGER = 0 + self.ZTRIGGER = 0 + self.CONFIRM = -10 + self.StartTiime = time.time() + self.HOME = 0 + self.A = 0 + self.B = 0 + self.wm = None + self.wiiPendantConnected = False + + if self.connect(): + self.Send("system:connect") + else: + print("no controllers found") + + def Send(self,command): + ''' + sends a put request to the webcontrol flask / socket io server at port 5000 + the /pendant in the address directs the server what commands to interpret + input is the command that is set by the wiimote button press + ''' + URL = "http://localhost:5000/pendant" + try: + r=requests.put(URL,command) + print (r) + except requests.exceptions.HTTPError as errh: + print ("Http Error:",errh) + except requests.exceptions.ConnectionError as errc: + print ("Error Connecting:",errc) + except requests.exceptions.Timeout as errt: + print ("Timeout Error:",errt) + except requests.exceptions.RequestException as err: + print ("OOps: Something Else",err) + + def connect(self): + ''' + try to establish bluetooth communication with wii controller + once connected, set LED to indicate distance + set to button mode or it won't work at all + if no connection, count and then return + + funciton returns + True when it connects + False after 10 timeouts + + ''' + i=2 + while not self.wm: + try: + self.wm=cwiid.Wiimote() + self.wiiPendantConnected = True + self.wm.led = self.L[self.LED_ON] + self.wm.rpt_mode = cwiid.RPT_BTN + return(True) + except RuntimeError: + if (i>5): + return(False) + #print ("Error opening wiimote connection" ) + time.sleep(5) + print ("attempt " + str(i)) + i += 1 +#end init + + def rumble(self,mode=0): + ''' + rumble shakes the wiimote when called. short time delays vary the shake pattern + ''' + if mode == 0: # start up heartbeat = 2 quick rumbles / prompt for confirmation + self.wm.rumble=True + time.sleep(.2) + self.wm.rumble = False + time.sleep(0.1) + self.wm.rumble=True + time.sleep(.2) + self.wm.rumble = False + + if mode == 1: # shutdown or timeout + self.wm.rumble=True + time.sleep(.1) + self.wm.rumble = False + time.sleep(0.1) + self.wm.rumble=True + time.sleep(.2) + self.wm.rumble = False + + if mode == 2: # shutdown or timeout + self.wm.rumble=True + time.sleep(.3) + self.wm.rumble = False + time.sleep(0.1) + self.wm.rumble=True + time.sleep(.3) + self.wm.rumble = False + + if mode >= 30: # shutdown or timeout + self.wm.rumble=True + time.sleep(.5) + self.wm.rumble = False +#end rumble + + def read_buttons(self): + if (self.wiiPendantConnected == False): + time.sleep(10) + print ("connecting") + if (self.connect()): + print("connected") + while(self.wiiPendantConnected == True): + # not using classic, this is if the remote is standing up though you hold it sideways + if (self.CONFIRM > 0): + elapsed = 1 - (time.time() - self.startTime) + if elapsed > 5: + self.rumble(1) # cancelled due to timeout + self.CONFIRM = - 10 # go back to normal + + if (self.wm.state['buttons'] & cwiid.BTN_A): + if (self.A == 0): + if (self.wm.state['buttons'] & cwiid.BTN_HOME): + print ("Wiimote MOVE SLED TO HOME") + self.Send("sled:home") + self.rumble(1) + self.A = 1 + if (self.wm.state['buttons'] & cwiid.BTN_B): + print("Wii Remote Disconnect") + self.Send("system:disconnect") + self.wiiPendantConnected = False + self.rumble(0) + self.wm = None + return # this should kill the process... if not how to do it? + else: + self.A = 0 + + if (self.wm.state['buttons'] & cwiid.BTN_B): + if (self.B == 0): + if (self.wm.state['buttons'] & cwiid.BTN_RIGHT): + print("Wiimote Start") + self.rumble(1) + self.B = 1 + self.Send("gcode:startRun") + if (self.wm.state['buttons'] & cwiid.BTN_UP): + print("Wiimote Pause") + self.rumble(1) + self.B = 1 + self.Send("gcode:pauseRun") + if (self.wm.state['buttons'] & cwiid.BTN_DOWN): + print("Wiimote Resume") + self.rumble(1) + self.B = 1 + self.Send("gcode:resumeRun") + if (self.wm.state['buttons'] & cwiid.BTN_LEFT): + print("Wiimote Stop") + self.rumble(1) + self.B = 1 + self.Send("gcode:stopRun") + elif (self.wm.state['buttons'] & cwiid.BTN_A): + print("Wii Remote Disconnect") + self.Send("system:disconnect") + self.wiiPendantConnected = False + self.rumble(0) + self.wm = None + return + else: + self.B = 0 + + if (self.wm.state['buttons'] & cwiid.BTN_1): + if self.TRIGGER == 0: + if (self.wm.state['buttons'] & cwiid.BTN_UP): + print("Wiimote MOVE SLED LEFT") + self.rumble(1) + self.TRIGGER = 1 + self.Send("sled:left:" + str(self.DISTANCE[self.LED_ON])) + if (self.wm.state['buttons'] & cwiid.BTN_DOWN): + print("Wiimote MOVE SLED RIGHT") + self.rumble(1) + self.TRIGGER = 1 + self.RIGHT = 0 + self.Send("sled:right:" + str(self.DISTANCE[self.LED_ON])) + if (self.wm.state['buttons'] & cwiid.BTN_RIGHT): + print("Wiimote MOVE SLED UP") + self.rumble(1) + self.TRIGGER = 1 + self.UP = 0 + self.Send("sled:up:" + str(self.DISTANCE[self.LED_ON])) + if (self.wm.state['buttons'] & cwiid.BTN_LEFT): + print("Wiimote MOVE SLED DOWN") + self.rumble(1) + self.TRIGGER = 1 + self.DOWN = 0 + self.Send("sled:down:" + str(self.DISTANCE[self.LED_ON])) + if (self.wm.state['buttons'] & cwiid.BTN_HOME): + print("Wiimote SET NEW HOME POSITION") + self.rumble(1) + self.TRIGGER = 1 + self.Send("sled:defineHome") + else: + self.TRIGGER = 0 + + if (self.wm.state['buttons'] & cwiid.BTN_2): + if self.ZTRIGGER == 0: + self.TRIGGER = 0 + if (self.wm.state['buttons'] & cwiid.BTN_RIGHT): + print("Wiimote MOVE Z UP") + self.rumble(2) + self.ZTRIGGER = 1 + self.Send("zAxis:raise:" + str(self.Z[self.LED_ON])) + if (self.wm.state['buttons'] & cwiid.BTN_LEFT): + print("Wiimote MOVE Z DOWN") + self.rumble(2) + self.ZTRIGGER = 1 + self.Send("zAxis:lower:"+ str(self.Z[self.LED_ON])) + if (self.wm.state['buttons'] & cwiid.BTN_UP): + print("Wiimote stop Z axis") + self.rumble(2) + self.ZTRIGGER = 1 + self.Send("zAxis:stopZ") + if (self.wm.state['buttons'] & cwiid.BTN_HOME): + print("Wiimote Reset Z AXIS to 0") + self.rumble(2) + self.ZTRIGGER = 1 + self.Send("zAxis:defineZ0") + else: + self.ZTRIGGER = 0 + + if (self.wm.state['buttons'] & cwiid.BTN_MINUS): + if self.MINUS == 0: + self.MINUS = 1 + self.LED_ON = self.LED_ON - 1 + if self.LED_ON < 0: + self.LED_ON = 3 + print("Sled Move Distance is ", self.DISTANCE[self.LED_ON]) + print("Z Distance is ", self.Z[self.LED_ON]) + self.wm.led = self.L[self.LED_ON] + else: + self.MINUS = 0 + + if (self.wm.state['buttons'] & cwiid.BTN_PLUS): + if self.PLUS == 0: + self.PLUS = 1 + self.LED_ON = self.LED_ON + 1 + if self.LED_ON > 3: + self.LED_ON = 0 + print("Sled move Distance is ", self.DISTANCE[self.LED_ON]) + print("Z Distance is ", self.Z[self.LED_ON]) + self.wm.led = self.L[self.LED_ON] + else: + self.PLUS = 0 + #return True + + #end button scan +#END class + + +def main(): + wp = WiiPendant() # instantiate a wiipendant object named wp + #while True: + wp.read_buttons() # read the buttons in the wp object + + # when the remote is disconnected, the program stops + # datetime A combination of a date and a time. Attributes: () +if __name__ == "__main__": + main() diff --git a/Services/MaslowPendant.service b/Services/MaslowPendant.service new file mode 100644 index 00000000..4f15877c --- /dev/null +++ b/Services/MaslowPendant.service @@ -0,0 +1,14 @@ +[Unit] +Description=Maslow Wiimote Input +After=network-online.target + +[Service] +ExecStart=/usr/bin/python3 /usr/local/etc/MaslowPendant.py +WorkingDirectory=/usr/local/etc +StandardOutput=inherit +StandardError=inherit +Restart=never +User=pi + +[Install] +WantedBy=multi-user.target diff --git a/Services/MaslowTextDisplay.py b/Services/MaslowTextDisplay.py new file mode 100644 index 00000000..060104d7 --- /dev/null +++ b/Services/MaslowTextDisplay.py @@ -0,0 +1,17 @@ +#!/usr/bin/python3 + +import requests +import json + +while True: + data = Get('LED','stuff') + if (items != None): + flag = items["data"]["flag"] + index = items["data"]["index"] + moving = items["data"]["moving"] + zMove = items["data"]["zMove"] + wiiPendantPresent = items["data"]["wiiPendantPresent"] + #print (flag) + #print (index) + #print (moving) + print(items) \ No newline at end of file diff --git a/Services/MaslowWC.service b/Services/MaslowWC.service new file mode 100644 index 00000000..73ab4973 --- /dev/null +++ b/Services/MaslowWC.service @@ -0,0 +1,15 @@ +[Unit] +Description=Maslow WebControl +After=network-online.target + +[Service] +Type=simple +ExecStart=/usr/bin/python3 /home/pi/wiiControl/main.py +WorkingDirectory=/home/pi/wiiControl +StandardOutput=inherit +StandardError=inherit +Restart=never +user=pi + +[Install] +WantedBy=sysinit.target \ No newline at end of file diff --git a/Services/get.py b/Services/get.py new file mode 100644 index 00000000..95079b8c --- /dev/null +++ b/Services/get.py @@ -0,0 +1,45 @@ +#!/usr/bin/python3 + +#get.py + +import requests + +def Get(address,command): + try: + URL = "http://localhost:5000/" + str(address) + #print (URL) + r = requests.get(URL,params = command) + #print (r.text) + return r.json() + except: + print ('error getting data, check server') + return ('error:error') + +flag = '0' +items = Get('LED','stuff') +if (items != None): + if (flag == "0"): + if(items["data"]["flag"] == "1"): + pass#start_time = time.time() + else: + if(items["data"]["flag"] == "0"): + pass# stop_time = time.time() + flag = items["data"]["flag"] + index = items["data"]["index"] + moving = items["data"]["moving"] + zMove = items["data"]["zMove"] + wiiPendantPresent = bool(items["data"]["wiiPendantPresent"]) + wiiconnected = bool(items["data"]["wiiconnected"]) + clidisplay = bool(items["data"]["clidisplay"]) + sledX = float(items["data"]["sled_location_X"]) + sledY = float(items["data"]["sled_location_y"]) + #"sled_location_z": str(app.data.zval), \ + homeX = float(items["data"]["home_location_x"]) + homeY = float(items["data"]["home_location_y"]) + xmin = items["data"]["gcode_min_x"] + xmax = float(items["data"]["gcode_max_x"]) + ymin = items["data"]["gcode_min_y"] + ymax = float(items["data"]["gcode_max_y"]) + #print (index) + #print (moving) + print(items) diff --git a/Services/readme.rm b/Services/readme.rm new file mode 100644 index 00000000..1e4084a1 --- /dev/null +++ b/Services/readme.rm @@ -0,0 +1,31 @@ +To set up buttons: + +go to webcontrol/Services folder + +chmod 777 * + +sudo copy the following files from /Service to /usr/local/etc/ + +MaslowButtonRestart.sh +MaslowButtonStart.sh +MaslowButtonStop.sh +MaslowPendantStart.sh +MaslowPendantRestart.sh +MaslowPendantStop.sh +MaslowButton.py +MaslwoPendant.py + + +sudo copy the following files /Service to /etc/systemd/system/ + +MaslowButton.service +MaslowPendant.service + +This service requires the installation of the cwiid library compiled for python 3 + +git clone https://github.com/Orob-Maslow/python3-wiimote.git +aclocal +autoconf +./configure +make +sudo make install diff --git a/Services/requirements.txt b/Services/requirements.txt new file mode 100644 index 00000000..e282bc21 --- /dev/null +++ b/Services/requirements.txt @@ -0,0 +1,2 @@ +cwiid +requests diff --git a/Services/t.py b/Services/t.py new file mode 100644 index 00000000..b20347aa --- /dev/null +++ b/Services/t.py @@ -0,0 +1,32 @@ +#!/usr/bin/python3 + +import requests + +URL = "http://localhost:5000/GPIO" + +r=requests.put(URL, "gcode:startRun") +r=requests.put(URL, "gcode:pauseRun") +r=requests.put(URL, "gcode:stopRun") +r=requests.put(URL, "move:up") +r=requests.put(URL, "move:down") +r=requests.put(URL, "move:left") +r=requests.put(URL, "move:right") + +URL = "http://localhost:5000/pendant" + +r=requests.put(URL, "system:connected") +r=requests.put(URL, "system:disconnect") +r=requests.put(URL, "gcode:startRun") +r=requests.put(URL, "gcode:pauseRun") +r=requests.put(URL, "gcode:resumeRun") +r=requests.put(URL, "gcode:stopRun") +r=requests.put(URL, "sled:up") +r=requests.put(URL, "sled:down") +r=requests.put(URL, "sled:left") +r=requests.put(URL, "sled:right") +r=requests.put(URL, "zAxis:raise") +r=requests.put(URL, "zAxis:lower") +r=requests.put(URL, "zAxis:stopZ") +r=requests.put(URL, "zAxis:defineZ0") +r=requests.put(URL, "sled:home") +r=requests.put(URL, "sled:defineHome") diff --git a/WebPageProcessor/__init__.py b/WebPageProcessor/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/WebPageProcessor/webPageProcessor.py b/WebPageProcessor/webPageProcessor.py new file mode 100644 index 00000000..3d8d8b42 --- /dev/null +++ b/WebPageProcessor/webPageProcessor.py @@ -0,0 +1,698 @@ +from __main__ import socketio + +import time +import math +import json +from os import listdir +from os.path import isfile, join +import re +from flask import render_template +import os +import frontmatter +import webbrowser +import socket +from github import Github +import markdown + + +class WebPageProcessor: + + data = None + + def __init__(self, data): + self.data = data + + def createWebPage(self, pageID, isMobile, args): + # returns a page and a bool specifying whether the user has to click close to exit modal + if pageID == "maslowSettings": + setValues = self.data.config.getJSONSettingSection("Maslow Settings") + # because this page allows you to select the comport from a list that is not stored in webcontrol.json, we need to package and send the list of comports + # Todo:? change it to store the list? + ports = self.data.comPorts + if self.data.controllerFirmwareVersion < 100: + enableCustom = False + else: + enableCustom = True + if isMobile: + page = render_template( + "settings_mobile.html", + title="Maslow Settings", + settings=setValues, + ports=ports, + pageID="maslowSettings", + enableCustom=enableCustom, + ) + else: + page = render_template( + "settings.html", + title="Maslow Settings", + settings=setValues, + ports=ports, + pageID="maslowSettings", + enableCustom=enableCustom, + ) + return page, "Maslow Settings", False, "medium", "content", "footerSubmit" + elif pageID == "advancedSettings": + setValues = self.data.config.getJSONSettingSection("Advanced Settings") + if self.data.controllerFirmwareVersion < 100: + enableCustom = False + else: + enableCustom = True + if isMobile: + page = render_template( + "settings_mobile.html", + title="Advanced Settings", + settings=setValues, + pageID="advancedSettings", + enableCustom=enableCustom, + ) + else: + page = render_template( + "settings.html", + title="Advanced Settings", + settings=setValues, + pageID="advancedSettings", + enableCustom=enableCustom, + ) + return page, "Advanced Settings", False, "medium", "content", "footerSubmit" + elif pageID == "webControlSettings": + setValues = self.data.config.getJSONSettingSection("WebControl Settings") + if self.data.controllerFirmwareVersion < 100: + enableCustom = False + else: + enableCustom = True + if isMobile: + page = render_template( + "settings_mobile.html", + title="WebControl Settings", + settings=setValues, + pageID="webControlSettings", + enableCustom=enableCustom, + ) + else: + page = render_template( + "settings.html", + title="WebControl Settings", + settings=setValues, + pageID="webControlSettings", + enableCustom=enableCustom, + ) + return page, "WebControl Settings", False, "medium", "content", "footerSubmit" + elif pageID == "cameraSettings": + setValues = self.data.config.getJSONSettingSection("Camera Settings") + if self.data.controllerFirmwareVersion < 100: + enableCustom = False + else: + enableCustom = True + if isMobile: + page = render_template( + "settings_mobile.html", + title="Camera Settings", + settings=setValues, + pageID="cameraSettings", + enableCustom=enableCustom, + ) + else: + page = render_template( + "settings.html", + title="Camera Settings", + settings=setValues, + pageID="cameraSettings", + enableCustom=enableCustom, + ) + return page, "Camera Settings", False, "medium", "content", "footerSubmit" + elif pageID == "gpioSettings": + setValues = self.data.config.getJSONSettingSection("GPIO Settings") + if self.data.controllerFirmwareVersion < 100: + enableCustom = False + else: + enableCustom = True + options = self.data.gpioActions.getActionList() + if isMobile: + page = render_template( + "gpio_mobile.html", + title="GPIO Settings", + settings=setValues, + options=options, + pageID="gpioSettings", + enableCustom=enableCustom, + ) + else: + page = render_template( + "gpio.html", + title="GPIO Settings", + settings=setValues, + options=options, + pageID="gpioSettings", + enableCustom=enableCustom, + ) + return page, "GPIO Settings", False, "medium", "content", "footerSubmit" + elif pageID == "openGCode": + lastSelectedFile = self.data.config.getValue("Maslow Settings", "openFile") + print(lastSelectedFile) + lastSelectedDirectory = self.data.config.getValue("Computed Settings", "lastSelectedDirectory") + home = self.data.config.getHome() + homedir = home+"/.WebControl/gcode" + directories = [] + files = [] + try: + for _root, _dirs, _files in os.walk(homedir): + if _dirs: + directories = _dirs + for file in _files: + if _root != homedir: + _dir = _root.split("\\")[-1].split("/")[-1] + else: + _dir = "." + files.append({"directory":_dir, "file":file}) + except Exception as e: + print(e) + # files = [f for f in listdir(homedir) if isfile(join(homedir, f))] + directories.insert(0, "./") + if lastSelectedDirectory is None: + lastSelectedDirectory="." + page = render_template( + "openGCode.html", directories=directories, files=files, lastSelectedFile=lastSelectedFile, lastSelectedDirectory=lastSelectedDirectory, isOpen=True + ) + return page, "Open GCode", False, "medium", "content", "footerSubmit" + elif pageID == "saveGCode": + lastSelectedFile = self.data.config.getValue("Maslow Settings", "openFile") + print(lastSelectedFile) + lastSelectedDirectory = self.data.config.getValue("Computed Settings", "lastSelectedDirectory") + home = self.data.config.getHome() + homedir = home + "/.WebControl/gcode" + directories = [] + files = [] + try: + for _root, _dirs, _files in os.walk(homedir): + if _dirs: + directories = _dirs + for file in _files: + if _root != homedir: + _dir = _root.split("\\")[-1].split("/")[-1] + else: + _dir = "." + files.append({"directory": _dir, "file": file}) + except Exception as e: + print(e) + # files = [f for f in listdir(homedir) if isfile(join(homedir, f))] + directories.insert(0, "./") + if lastSelectedDirectory is None: + lastSelectedDirectory = "." + page = render_template( + "saveGCode.html", directories=directories, files=files, lastSelectedFile=lastSelectedFile, + lastSelectedDirectory=lastSelectedDirectory, isOpen=False + ) + return page, "Save GCode", False, "medium", "content", "footerSubmit" + + elif pageID == "uploadGCode": + validExtensions = self.data.config.getValue( + "WebControl Settings", "validExtensions" + ) + lastSelectedDirectory = self.data.config.getValue("Computed Settings", "lastSelectedDirectory") + home = self.data.config.getHome() + homedir = home + "/.WebControl/gcode" + directories = [] + try: + for _root, _dirs, _files in os.walk(homedir): + if _dirs: + directories = _dirs + except Exception as e: + print(e) + directories.insert(0, "./") + if lastSelectedDirectory is None: + lastSelectedDirectory = "." + page = render_template("uploadGCode.html", validExtensions=validExtensions, directories=directories, lastSelectedDirectory=lastSelectedDirectory) + return page, "Upload GCode", False, "medium", "content", "footerSubmit" + elif pageID == "importGCini": + url = "importFile" + page = render_template("importFile.html", url=url) + return page, "Import groundcontrol.ini", False, "medium", "content", False + elif pageID == "importWCJSON": + url = "importFileWCJSON" + page = render_template("importFile.html", url=url) + return page, "Import webcontrol.json", False, "medium", "content", False + elif pageID == "restoreWebControl": + url = "importRestoreWebControl" + page = render_template("importFile.html", url=url) + return page, "Restore WebControl", False, "medium", "content", False + elif pageID == "actions": + if self.data.controllerFirmwareVersion < 100: + enableCustom = False + else: + enableCustom = True + if self.data.controllerFirmwareVersion < 50: + enableHoley = False + else: + enableHoley = True + if ((self.data.platform == "RPI")or(self.data.platform == "PYINSTALLER")): + docker = True + enableRPIshutdown = True + #print("RPI shutdown is TRUE") + else: + docker = False + enableRPIshutdown = False + #print ("RPI shutdown is FALSE") + if self.data.pyInstallUpdateAvailable: + updateAvailable = True + updateRelease = self.data.pyInstallUpdateVersion + else: + updateAvailable = False + updateRelease = "N/A" + page = render_template("actions.html", updateAvailable=updateAvailable, updateRelease=updateRelease, docker=docker, customFirmwareVersion=self.data.customFirmwareVersion, stockFirmwareVersion=self.data.stockFirmwareVersion, holeyFirmwareVersion=self.data.holeyFirmwareVersion, enableCustom=enableCustom, enableHoley=enableHoley, enableRPIshutdown = enableRPIshutdown) + return page, "Actions", False, "large", "content", False + elif pageID == "zAxis": + socketio.emit("closeModals", {"data": {"title": "Actions"}}, namespace="/MaslowCNC") + distToMoveZ = self.data.config.getValue("Computed Settings", "distToMoveZ") + unitsZ = self.data.config.getValue("Computed Settings", "unitsZ") + touchPlate = self.data.config.getValue("Advanced Settings", "touchPlate") + if isMobile: + page = render_template("zaxis_mobile.html", distToMoveZ=distToMoveZ, unitsZ=unitsZ, touchPlate=touchPlate) + else: + page = render_template("zaxis.html", distToMoveZ=distToMoveZ, unitsZ=unitsZ, touchPlate=touchPlate) + return page, "Z-Axis", False, "medium", "content", False + elif pageID == "setSprockets": + if self.data.controllerFirmwareVersion < 100: + fourMotor = False + else: + fourMotor = True + chainExtendLength = self.data.config.getValue("Advanced Settings", "chainExtendLength") + socketio.emit("closeModals", {"data": {"title": "Actions"}}, namespace="/MaslowCNC") + if isMobile: + page = render_template("setSprockets_mobile.html", chainExtendLength=chainExtendLength, fourMotor=fourMotor) + else: + page = render_template("setSprockets.html", chainExtendLength=chainExtendLength, fourMotor=fourMotor) + return page, "Set Sprockets", False, "medium", "content", False + elif pageID == "resetChains": + if self.data.controllerFirmwareVersion < 100: + fourMotor = False + else: + fourMotor = True + chainExtendLength = self.data.config.getValue("Advanced Settings", "chainExtendLength") + socketio.emit("closeModals", {"data": {"title": "Actions"}}, namespace="/MaslowCNC") + if isMobile: + page = render_template("resetChains_mobile.html", chainExtendLength=chainExtendLength, fourMotor=fourMotor) + else: + page = render_template("resetChains.html", chainExtendLength=chainExtendLength, fourMotor=fourMotor) + return page, "Reset Chains", False, "medium", "content", False + + elif pageID == "triangularCalibration": + socketio.emit("closeModals", {"data": {"title": "Actions"}}, namespace="/MaslowCNC") + motorYoffset = self.data.config.getValue("Maslow Settings", "motorOffsetY") + rotationRadius = self.data.config.getValue("Advanced Settings", "rotationRadius") + chainSagCorrection = self.data.config.getValue( + "Advanced Settings", "chainSagCorrection" + ) + page = render_template( + "triangularCalibration.html", + pageID="triangularCalibration", + motorYoffset=motorYoffset, + rotationRadius=rotationRadius, + chainSagCorrection=chainSagCorrection, + ) + return page, "Triangular Calibration", True, "medium", "content", False + elif pageID == "holeyCalibration": + socketio.emit("closeModals", {"data": {"title": "Actions"}}, namespace="/MaslowCNC") + motorYoffset = self.data.config.getValue("Maslow Settings", "motorOffsetY") + distanceBetweenMotors = self.data.config.getValue("Maslow Settings", "motorSpacingX") + leftChainTolerance = self.data.config.getValue("Advanced Settings", "leftChainTolerance") + rightChainTolerance = self.data.config.getValue("Advanced Settings", "rightChainTolerance") + page = render_template( + "holeyCalibration.html", + pageID="holeyCalibration", + motorYoffset=motorYoffset, + distanceBetweenMotors=distanceBetweenMotors, + leftChainTolerance=leftChainTolerance, + rightChainTolerance=rightChainTolerance, + ) + return page, "Holey Calibration", True, "medium", "content", False + elif pageID == "quickConfigure": + socketio.emit("closeModals", {"data": {"title": "Actions"}}, namespace="/MaslowCNC") + motorOffsetY = self.data.config.getValue("Maslow Settings", "motorOffsetY") + rotationRadius = self.data.config.getValue("Advanced Settings", "rotationRadius") + kinematicsType = self.data.config.getValue("Advanced Settings", "kinematicsType") + if kinematicsType != "Quadrilateral": + if abs(float(rotationRadius) - 138.4) < 0.01: + kinematicsType = "Ring" + else: + kinematicsType = "Custom" + motorSpacingX = self.data.config.getValue("Maslow Settings", "motorSpacingX") + chainOverSprocket = self.data.config.getValue( + "Advanced Settings", "chainOverSprocket" + ) + print("MotorOffsetY=" + str(motorOffsetY)) + page = render_template( + "quickConfigure.html", + pageID="quickConfigure", + motorOffsetY=motorOffsetY, + rotationRadius=rotationRadius, + kinematicsType=kinematicsType, + motorSpacingX=motorSpacingX, + chainOverSprocket=chainOverSprocket, + ) + return page, "Quick Configure", False, "medium", "content", False + elif pageID == "screenAction": + print(args["x"]) + page = render_template("screenAction.html", posX=args["x"], posY=args["y"]) + return page, "Screen Action", False, "medium", "content", False + elif pageID == "viewGcode": + page = render_template("viewGcode.html", gcode=self.data.gcode) + return page, "View GCode", False, "medium", "content", False + elif pageID == "editGCode": + text = "" + for line in self.data.gcode: + text = text + line + "\n" + #text = self.gcodePreProcessor() + page = render_template("editGCode.html", gcode=text.rstrip(), pageID="editGCode",) + return page, "Edit GCode", True, "medium", "content", "footerSubmit" + elif pageID == "sendGCode": + text = self.data.sentCustomGCode + page = render_template("editGCode.html", gcode=text, pageID="sendGCode", ) + return page, "Edit GCode", True, "medium", "content", "footerSubmit" + elif pageID == "pidTuning": + if self.data.controllerFirmwareVersion < 100: + fourMotor = False + else: + fourMotor = True + KpP = self.data.config.getValue("Advanced Settings", "KpPos") + KiP = self.data.config.getValue("Advanced Settings", "KiPos") + KdP = self.data.config.getValue("Advanced Settings", "KdPos") + KpV = self.data.config.getValue("Advanced Settings", "KpV") + KiV = self.data.config.getValue("Advanced Settings", "KiV") + KdV = self.data.config.getValue("Advanced Settings", "KdV") + vVersion = "1" + pVersion = "1" + page = render_template("pidTuning.html", + KpP=KpP, + KiP=KiP, + KdP=KdP, + KpV=KpV, + KiV=KiV, + KdV=KdV, + vVersion=vVersion, + pVersion=pVersion, + fourMotor=fourMotor) + return page, "PID Tuning", False, "large", "content", False + elif pageID == "editBoard": + board = self.data.boardManager.getCurrentBoard() + scale = 1 + units = "inches" + if self.data.units == "MM": + scale = 25.4 + units = "mm" + if isMobile: + pageName = "editBoard_mobile.html" + else: + pageName = "editBoard.html" + page = render_template(pageName, + units=units, + boardID=board.boardID, + material=board.material, + height=round(board.height*scale, 2), + width=round(board.width*scale, 2), + thickness=round(board.thickness*scale, 2), + centerX=round(board.centerX*scale, 2), + centerY=round(board.centerY*scale, 2), + routerHorz=self.data.xval, + routerVert=self.data.yval, + pageID="editBoard") + return page, "Create/Edit Board", False, "medium", "content", "footerSubmit" + elif pageID == "trimBoard": + board = self.data.boardManager.getCurrentBoard() + scale = 1 + units = "inches" + if self.data.units == "MM": + scale = 25.4 + units = "mm" + if isMobile: + pageName = "trimBoard.html" + else: + pageName = "trimBoard.html" + page = render_template(pageName, + units=units, + pageID="trimBoard") + return page, "Trim Board", False, "medium", "content", "footerSubmit" + elif pageID == "saveBoard": + #lastSelectedFile = self.data.config.getValue("Maslow Settings", "openBoardFile") + #print(lastSelectedFile) + lastSelectedDirectory = self.data.config.getValue("Computed Settings", "lastSelectedBoardDirectory") + lastSelectedFile = self.data.boardManager.getCurrentBoardFilename() + home = self.data.config.getHome() + homedir = home + "/.WebControl/boards" + directories = [] + files = [] + try: + for _root, _dirs, _files in os.walk(homedir): + if _dirs: + directories = _dirs + for file in _files: + if _root != homedir: + _dir = _root.split("\\")[-1].split("/")[-1] + else: + _dir = "." + files.append({"directory": _dir, "file": file}) + except Exception as e: + print(e) + # files = [f for f in listdir(homedir) if isfile(join(homedir, f))] + directories.insert(0, "./") + if lastSelectedDirectory is None: + lastSelectedDirectory = "." + page = render_template( + "saveBoard.html", directories=directories, files=files, lastSelectedFile=lastSelectedFile, + lastSelectedDirectory=lastSelectedDirectory, isOpen=False + ) + return page, "Save Board", False, "medium", "content", "footerSubmit" + elif pageID == "openBoard": + lastSelectedFile = self.data.config.getValue("Maslow Settings", "openBoardFile") + print(lastSelectedFile) + lastSelectedDirectory = self.data.config.getValue("Computed Settings", "lastSelectedBoardDirectory") + home = self.data.config.getHome() + homedir = home+"/.WebControl/boards" + directories = [] + files = [] + try: + for _root, _dirs, _files in os.walk(homedir): + if _dirs: + directories = _dirs + for file in _files: + if _root != homedir: + _dir = _root.split("\\")[-1].split("/")[-1] + else: + _dir = "." + files.append({"directory":_dir, "file":file}) + except Exception as e: + print(e) + # files = [f for f in listdir(homedir) if isfile(join(homedir, f))] + directories.insert(0, "./") + if lastSelectedDirectory is None: + lastSelectedDirectory="." + page = render_template( + "openBoard.html", directories=directories, files=files, lastSelectedFile=lastSelectedFile, lastSelectedDirectory=lastSelectedDirectory, isOpen=True + ) + return page, "Open Board", False, "medium", "content", "footerSubmit" + elif pageID == "about": + version = self.data.pyInstallCurrentVersion + if isMobile: + pageName = "about.html" + else: + pageName = "about.html" + page = render_template(pageName, pageID="about", version=version) + return page, "About", False, "medium", "content", False + elif pageID == "gettingStarted": + if isMobile: + pageName = "gettingStarted.html" + else: + pageName = "gettingStarted.html" + page = render_template(pageName, pageID="gettingStarted") + return page, "Getting Started", False, "medium", "content", False + elif pageID == "releases": + releases = self.data.releaseManager.getReleases() + latestRelease = self.data.releaseManager.getLatestRelease() + currentRelease = "v"+str(self.data.pyInstallCurrentVersion) + for release in releases: + tag_name = re.sub(r'[v]', r'', release.tag_name) + if isMobile: + page = render_template( + "releases_mobile.html", + title="Update Manager", + releases=releases, + latestRelease=latestRelease, + currentRelease=currentRelease, + pageID="releases", + ) + else: + page = render_template( + "releases.html", + title="Update Manager", + releases=releases, + latestRelease=latestRelease, + currentRelease=currentRelease, + pageID="releases", + ) + return page, "Update Manager", False, "medium", "content", False + elif pageID == "helpPages": + helpPages = self.data.helpManager.getHelpPages() + if isMobile: + page = render_template( + "helpPages_mobile.html", + title="Help", + helpPages=helpPages, + pageID="help", + ) + else: + page = render_template( + "helpPages.html", + title="Help", + helpPages=helpPages, + pageID="help", + ) + return page, "Help", False, "medium", "content", False + elif pageID == "fakeServo": + if isMobile: + page = render_template( + "fakeServo.html", + title="Fake Servo", + pageID="fakeServo", + ) + else: + page = render_template( + "fakeServo.html", + title="Fake Servo", + pageID="fakeServo", + ) + return page, "Fake Servo", False, "small", "content", False + elif pageID == "help": + helpIndex = self.getPage("/docs/assets/helpPages.md", isMobile) + helpPage = self.getPage("/docs/index.md", isMobile) + if isMobile: + page = render_template( + "help_mobile.html", + title="Help", + helpIndex=helpIndex, + helpPage=helpPage, + pageID="help", + ) + else: + page = render_template( + "help.html", + title="Help", + helpIndex=helpIndex, + helpPage=helpPage, + pageID="help", + ) + return page, "Help", False, "large", "content", False + else: + pageParts = pageID.split("/") + if len(pageParts) > 1: + # help page + print(pageParts) + helpIndex = self.getPage("/docs/assets/helpPages.md", isMobile) + helpPage = self.getPage("/docs/"+pageID, isMobile) + if isMobile: + helpIndex = self.createLinks(pageParts) + page = render_template( + "help_mobile.html", + title="Help", + helpIndex=helpIndex, + helpPage=helpPage, + pageID="help", + ) + else: + page = render_template( + "help.html", + title="Help", + helpIndex=helpIndex, + helpPage=helpPage, + pageID="help", + ) + #print(page) + return page, "Help", False, "large", "content", False + + else: + self.data.ui_queue1.put("Alert", "Alert", "Function not currently implemented.. Sorry.") + + def gcodePreProcessor(self): + text = "" + for line in self.data.gcode: + text=text+line+"\n" + return text + + def getPage(self, pageName, isMobile): + if self.data.platform == "PYINSTALLER": + lhome = os.path.join(self.data.platformHome) + else: + lhome = "." + filename = lhome+pageName + if filename.find("http") != -1: + print("external link") + return None + with open(filename) as f: + page = frontmatter.loads(f.read()) + pageContent = page.content + #filterString = '([^\!]|^)\[(.+)\]\((.+)\)' + filterString = '(?:[^\!]|^)\[([^\[\]]+)\]\((?!http)([^()]+)\)' + filteredPage = re.sub(filterString, r"""\1""", pageContent) + filteredPage = filteredPage.replace("{{ site.baseurl }}{% link ","") + filteredPage = filteredPage.replace(".md %}", ".md") + filteredPage = markdown.markdown(filteredPage, extensions=["markdown.extensions.tables"]) + filteredPage = filteredPage.replace("Â", "") + filteredPage = filteredPage.replace("{: .label .label-blue }", "") + filteredPage = filteredPage.replace("", "") + + if isMobile: + # make all images 100% + filteredPage = filteredPage.replace("img alt=", "img width='100%' alt=") + + return filteredPage + + def createLinks(self, pageParts): + link = "Home" + #assets/actions/Diagnostics Maintenance/index.md + if len(pageParts) == 4 and pageParts[3]=='index.md': + # third level index with form like: + # ['assets', 'actions', 'Diagnostics Maintenance', 'index.md'] + forward = "assets/" + pageParts[1] + "/" + pageLink = " / "+pageParts[1]+"" + link = link + pageLink + return link + if len(pageParts) == 3 and pageParts[2].endswith(".md") and pageParts[2] != "index.md": + # fourth level index with form like: + # ['Actions', 'Diagnostics Maintenance', 'testMotorsEncoders.md'] + forward = "assets/"+pageParts[0]+ "/index.md" + pageLink = " / "+pageParts[0]+"" + link = link + pageLink + forward = "assets/"+pageParts[0]+"/"+pageParts[1] + "/index.md" + pageLink = " / "+pageParts[1]+"" + link = link + pageLink + return link + if len(pageParts) == 3 and pageParts[2].endswith(".md") and pageParts[2] == "index.md": + # second level index with form like: + # ['assets', 'actions', 'index.md'] + return link + + return link + + + ''' + elif pageID == "opticalCalibration": + socketio.emit("closeModals", {"data": {"title": "Actions"}}, namespace="/MaslowCNC") + opticalCenterX = self.data.config.getValue("Optical Calibration Settings", "opticalCenterX") + opticalCenterY = self.data.config.getValue("Optical Calibration Settings", "opticalCenterY") + scaleX = self.data.config.getValue("Optical Calibration Settings", "scaleX") + scaleY = self.data.config.getValue("Optical Calibration Settings", "scaleY") + gaussianBlurValue = self.data.config.getValue("Optical Calibration Settings", "gaussianBlurValue") + cannyLowValue = self.data.config.getValue("Optical Calibration Settings", "cannyLowValue") + cannyHighValue = self.data.config.getValue("Optical Calibration Settings", "cannyHighValue") + autoScanDirection = self.data.config.getValue("Optical Calibration Settings", "autoScanDirection") + markerX = self.data.config.getValue("Optical Calibration Settings", "markerX") + markerY = self.data.config.getValue("Optical Calibration Settings", "markerY") + tlX = self.data.config.getValue("Optical Calibration Settings", "tlX") + tlY = self.data.config.getValue("Optical Calibration Settings", "tlY") + brX = self.data.config.getValue("Optical Calibration Settings", "brX") + brY = self.data.config.getValue("Optical Calibration Settings", "brY") + calibrationExtents = self.data.config.getValue("Optical Calibration Settings", "calibrationExtents") + positionTolerance = self.data.config.getValue("Optical Calibration Settings", "positionTolerance") + page = render_template("opticalCalibration.html", pageID="opticalCalibration", opticalCenterX=opticalCenterX, opticalCenterY=opticalCenterY, scaleX=scaleX, scaleY=scaleY, gaussianBlurValue=gaussianBlurValue, cannyLowValue=cannyLowValue, cannyHighValue=cannyHighValue, autoScanDirection=autoScanDirection, markerX=markerX, markerY=markerY, tlX=tlX, tlY=tlY, brX=brX, brY=brY, calibrationExtents=calibrationExtents, isMobile=isMobile, positionTolerance=positionTolerance) + return page, "Optical Calibration", True, "large", "content", False + ''' \ No newline at end of file diff --git a/app.py b/app.py index 9f14f7d8..e1c0d5dd 100644 --- a/app.py +++ b/app.py @@ -1,7 +1,18 @@ from flask import Flask from flask_mobility import Mobility from flask_socketio import SocketIO +from flask_misaka import Misaka -app = Flask(__name__) +import os, sys +base_dir = '.' +if hasattr(sys, '_MEIPASS'): + base_dir = os.path.join(sys._MEIPASS) + +md = Misaka() + +app = Flask(__name__, static_folder=os.path.join(base_dir, 'static'), template_folder=os.path.join(base_dir, 'templates')) +app.debug = True socketio = SocketIO(app) mobility = Mobility(app) +md.init_app(app) + diff --git a/buildFirmware.sh b/buildFirmware.sh new file mode 100644 index 00000000..6e080861 --- /dev/null +++ b/buildFirmware.sh @@ -0,0 +1,39 @@ +#!/bin/bash +rm -rf build +mkdir build +rm -rf firmware +mkdir firmware +cd firmware +mkdir madgrizzle +mkdir maslowcnc +mkdir holey + +cd ../build +madgrizzle_firmware_repo=https://github.com/madgrizzle/Firmware.git +madgrizzle_firmware_sha=bf4350ffd9bc154832505fc0125abd2c4c04dba7 +git clone $madgrizzle_firmware_repo firmware/madgrizzle +cd firmware/madgrizzle +git checkout $madgrizzle_firmware_sha +pio run -e megaatmega2560 + +mv .pio/build/megaatmega2560/firmware.hex ~/WebControl/firmware/madgrizzle/madgrizzle-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex + +cd ../.. + +maslowcnc_firmware_repo=https://github.com/MaslowCNC/Firmware.git +maslowcnc_firmware_sha=e1e0d020fff1f4f7c6b403a26a85a16546b7e15b +git clone $maslowcnc_firmware_repo firmware/maslowcnc +cd firmware/maslowcnc +git checkout $maslowcnc_firmware_sha +pio run -e megaatmega2560 +mv .pio/build/megaatmega2560/firmware.hex ~/WebControl/firmware/maslowcnc/maslowcnc-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex + +cd ../.. + +holey_firmware_repo=https://github.com/madgrizzle/Firmware.git +holey_firmware_sha=950fb23396171cbd456c2d4149455cc45f5e6bc3 +git clone $holey_firmware_repo firmware/holey +cd firmware/holey +git checkout $holey_firmware_sha +pio run -e megaatmega2560 +mv .pio/build/megaatmega2560/firmware.hex ~/WebControl/firmware/holey/holey-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex diff --git a/buildFirmware10.bat b/buildFirmware10.bat new file mode 100644 index 00000000..6fe6efdf --- /dev/null +++ b/buildFirmware10.bat @@ -0,0 +1,42 @@ + +del build /s /f /q +rmdir build /s/q +mkdir build + +del firmware /s /f /q +rmdir firmware /s /q +mkdir firmware +cd firmware +mkdir madgrizzle +mkdir maslowcnc +mkdir holey + +cd ../build +SET madgrizzle_firmware_repo=https://github.com/madgrizzle/Firmware.git +SET madgrizzle_firmware_sha=bf4350ffd9bc154832505fc0125abd2c4c04dba7 +git clone %madgrizzle_firmware_repo% firmware/madgrizzle +cd firmware/madgrizzle +git checkout %madgrizzle_firmware_sha% +pio run -e megaatmega2560 + +copy .pio/build/megaatmega2560/firmware.hex ~/WebControl/firmware/madgrizzle/madgrizzle-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex + +cd ../.. + +SET maslowcnc_firmware_repo=https://github.com/MaslowCNC/Firmware.git +SET maslowcnc_firmware_sha=e1e0d020fff1f4f7c6b403a26a85a16546b7e15b +git clone %maslowcnc_firmware_repo% firmware/maslowcnc +cd firmware/maslowcnc +git checkout %maslowcnc_firmware_sha% +pio run -e megaatmega2560 +copy .pio/build/megaatmega2560/firmware.hex ~/WebControl/firmware/maslowcnc/maslowcnc-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex + +cd ../.. + +SET holey_firmware_repo=https://github.com/madgrizzle/Firmware.git +SET holey_firmware_sha=950fb23396171cbd456c2d4149455cc45f5e6bc3 +git clone %holey_firmware_repo% firmware/holey +cd firmware/holey +git checkout %holey_firmware_sha% +pio run -e megaatmega2560 +copy .pio/build/megaatmega2560/firmware.hex C:\Users\jhogan\Documents\Github\WebControlfirmware/holey/holey-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex diff --git a/buildLinux1.sh b/buildLinux1.sh new file mode 100644 index 00000000..265fda5f --- /dev/null +++ b/buildLinux1.sh @@ -0,0 +1,57 @@ +#!/bin/bash +rm -rf build +mkdir build +rm -rf firmware +mkdir firmware +cd firmware +mkdir madgrizzle +mkdir maslowcnc +mkdir holey + +cd ../build +madgrizzle_firmware_repo=https://github.com/madgrizzle/Firmware.git +madgrizzle_firmware_sha=bf4350ffd9bc154832505fc0125abd2c4c04dba7 +git clone $madgrizzle_firmware_repo firmware/madgrizzle +cd firmware/madgrizzle +git checkout $madgrizzle_firmware_sha +pio run -e megaatmega2560 + +mv .pio/build/megaatmega2560/firmware.hex ~/WebControl/firmware/madgrizzle/madgrizzle-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex + +cd ../.. + +maslowcnc_firmware_repo=https://github.com/MaslowCNC/Firmware.git +maslowcnc_firmware_sha=e1e0d020fff1f4f7c6b403a26a85a16546b7e15b +git clone $maslowcnc_firmware_repo firmware/maslowcnc +cd firmware/maslowcnc +git checkout $maslowcnc_firmware_sha +pio run -e megaatmega2560 +mv .pio/build/megaatmega2560/firmware.hex ~/WebControl/firmware/maslowcnc/maslowcnc-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex + +cd ../.. + +holey_firmware_repo=https://github.com/madgrizzle/Firmware.git +holey_firmware_sha=950fb23396171cbd456c2d4149455cc45f5e6bc3 +git clone $holey_firmware_repo firmware/holey +cd firmware/holey +git checkout $holey_firmware_sha +pio run -e megaatmega2560 +mv .pio/build/megaatmega2560/firmware.hex ~/WebControl/firmware/holey/holey-$(sed -n -e 's/^.*VERSIONNUMBER //p' cnc_ctrl_v1/Maslow.h).hex + + +cd ~/WebControl +rm -r dist +pyinstaller main-onedir.spec +cd dist/main +touch webcontrol-linux-singledirectory.tar.gz +tar -zcvf webcontrol-linux-singledirectory.tar.gz --exclude=webcontrol-linux-singledirectory.tar.gz . +mv webcontrol-linux-singledirectory.tar.gz ../../releases + +cd ~/WebControl +rm -r dist +pyinstaller main.spec +cd dist +touch webcontrol-linux-singlefile.tar.gz +tar -zcvf webcontrol-linux-singlefile.tar.gz --exclude=webcontrol-linux-singlefile.tar.gz . +mv webcontrol-linux-singlefile.tar.gz ../releases + diff --git a/config/config.py b/config/config.py index e3946923..87fa7d96 100644 --- a/config/config.py +++ b/config/config.py @@ -7,23 +7,169 @@ """ import json import re +import os, sys +import math +from shutil import copyfile +from pathlib import Path +import time +import glob + from __main__ import app from DataStructures.makesmithInitFuncs import MakesmithInitFuncs class Config(MakesmithInitFuncs): settings = {} + defaults = {} + home = "." + home1 = "." + firstRun = False def __init__(self): + ''' + This function determines if a pyinstaller version is being run and if so, + sets the home directory of the pyinstaller files. This facilitates updates + to the pyinstaller releases. + ''' + self.home = str(Path.home()) + if hasattr(sys, '_MEIPASS'): + self.home1 = os.path.join(sys._MEIPASS) + print(self.home1) + + ''' + This portion creates directories that are missing and creates a new webcontrol.json + file if this is the first run (copies defaultwebcontrol.json) + ''' print("Initializing Configuration") - with open("webcontrol.json", "r") as infile: + if not os.path.isdir(self.home+"/.WebControl"): + print("creating "+self.home+"/.WebControl directory") + os.mkdir(self.home+"/.WebControl") + if not os.path.exists(self.home+"/.WebControl/webcontrol.json"): + print("copying defaultwebcontrol.json to "+self.home+"/.WebControl/") + copyfile(self.home1+"/defaultwebcontrol.json",self.home+"/.WebControl/webcontrol.json") + self.firstRun = True + if not os.path.isdir(self.home+"/.WebControl/gcode"): + print("creating "+self.home+"/.WebControl/gcode directory") + os.mkdir(self.home+"/.WebControl/gcode") + if not os.path.isdir(self.home+"/.WebControl/imports"): + print("creating "+self.home+"/.WebControl/imports directory") + os.mkdir(self.home+"/.WebControl/imports") + if not os.path.isdir(self.home+"/.WebControl/boards"): + print("creating "+self.home+"/.WebControl/boards directory") + os.mkdir(self.home+"/.WebControl/boards") + with open(self.home+"/.WebControl/webcontrol.json", "r") as infile: self.settings = json.load(infile) - # self.computeSettings(None, None, None, True); + # load default and see if there is anything missing.. if so, add it + ''' + This portion scans the webcontrol.json file and sees if anything is missing in comparison to + the defaultwebcontrol.json file. Changes to the defaultwebcontrol.json file are automatically + ADDED to the webcontrol.json file. This function does not DELETE entries in the webcontrol.json + file if they do not appear in the defaultwebcontrol.json file. + ''' + # TODO: add DELETE function to this to clean up unneeded entries + with open(self.home1+"/defaultwebcontrol.json", "r") as infile: + self.defaults = json.load(infile) + updated = False + for section in self.defaults: + sectionFound = False + for x in range(len(self.defaults[section])): + found = False + for _section in self.settings: + if _section == section: + sectionFound = True + for y in range(len(self.settings[_section])): + if self.defaults[section][x]["key"] == self.settings[_section][y]["key"]: + found = True + break + if found == False: + if sectionFound: + print("section found") + else: + print("section not found") + self.settings[section]=[] + print(section+"->"+self.defaults[section][x]["key"]+" was not found..") + t = {} + if "default" in self.defaults[section][x]: + t["default"]=self.defaults[section][x]["default"] + if "desc" in self.defaults[section][x]: + t["desc"]=self.defaults[section][x]["desc"] + if "firmwareKey" in self.defaults[section][x]: + t["firmwareKey"]=self.defaults[section][x]["firmwareKey"] + if "key" in self.defaults[section][x]: + t["key"]=self.defaults[section][x]["key"] + if "section" in self.defaults[section][x]: + t["section"]=self.defaults[section][x]["section"] + if "title" in self.defaults[section][x]: + t["title"]=self.defaults[section][x]["title"] + if "type" in self.defaults[section][x]: + t["type"]=self.defaults[section][x]["type"] + if "value" in self.defaults[section][x]: + t["value"]=self.defaults[section][x]["value"] + if "options" in self.defaults[section][x]: + t["options"]=self.defaults[section][x]["options"] + + self.settings[section].append(t) + print("added "+section+"->"+self.settings[section][len(self.settings[section])-1]["key"]) + updated = True + + ''' + If there was a change to webcontrol.json file due to differences with + defaultwebcontrol.json, then the config is reloaded. + ''' + if updated: + with open(self.home+"/.WebControl/webcontrol.json", "w") as outfile: + # print ("writing file") + json.dump( + self.settings, outfile, sort_keys=True, indent=4, ensure_ascii=False + ) + + ''' + Delete any copies of webcontrol in the downloads directory to cleanup the file system + ''' + home = self.home + dirName = home + "/.WebControl/downloads" + if os.path.exists(dirName): + dir = os.listdir(dirName) + for item in dir: + if item.startswith("webcontrol"): + if item.endswith("gz") or item.endswith("zip") or item.endswith("dmg"): + print("Removing file:"+item) + os.remove(os.path.join(dirName, item)) + + def checkForTouchedPort(self): + ''' + this function looks for a file that has a port number embedded + in the filename. If found, it parses the port number and uses it + to start the flask engine. + ''' + home = self.home + path = home+"/.WebControl/webcontrol-*.port" + print(path) + try: + for filename in glob.glob(path): + print(filename) + port = filename.split("-") + port = port[1].split(".port") + print(port[0]) + self.data.config.setValue("WebControl Settings", "webPort", port[0]) + os.remove(filename) + except Exception as e: + print(e) + return False + return True + + def getHome(self): + return self.home def getJSONSettings(self): return self.settings def updateQuickConfigure(self, result): + ''' + Updates settings based upon the form results. + :param result: submitted form + :return: always returns true. + ''' if result["kinematicsType"] == "Quadrilateral": self.setValue("Advanced Settings", "kinematicsType", "Quadrilateral") else: @@ -32,48 +178,84 @@ def updateQuickConfigure(self, result): self.setValue( "Advanced Settings", "chainOverSprocket", result["chainOverSprocket"] ) - self.setValue("Advanced Settings", "motorSpacingX", result["motorSpacingX"]) - self.setValue("Advanced Settings", "motorOffsetY", result["motorOffsetY"]) + self.setValue("Maslow Settings", "motorSpacingX", result["motorSpacingX"]) + self.setValue("Maslow Settings", "motorOffsetY", result["motorOffsetY"]) return True - def setValue(self, section, key, value, recursionBreaker=False): + def setValue(self, section, key, value, recursionBreaker=False, isImporting = False): + ''' + This function is intended to update a setting and call the necessary recomputes and syncs with the controller. + :param section: The section of the setting.. Advanced Settings, etc. + :param key: The key of the setting.. motorSpacingX, etc. + :param value: The value to set the setting to. + :param recursionBreaker: Prevents loops due to computed settings.. not sure is needed in reality. + :param isImporting: intended to delay sending settings and recomputing settings until import is done. + :return: + + Re: recursionBreaker. IIRC, I was having a heck of time getting settings to work, particularly when compute + settings was being called. computeSettings calls this function after computing a new value, but this function + calls computeSetting if a value is updated. To avoid testing on whether a setting is a computed setting or not, + computeSetting just sets recursionBreaker to true and this function doesn't call computeSetting. + ''' updated = False found = False + changedValue = None + changedKey = None + # Probably an easier way to do this than to iterate through all keys in a section to find the one you want to + # update. TODO: Find a pythonic way to find the key. for x in range(len(self.settings[section])): if self.settings[section][x]["key"].lower() == key.lower(): found = True + # each type (float, string, bool, etc.) is handled separately. This is approach is legacy, and could + # be cleaned up. TODO: cleanup this so it's handled with less redundancy. if self.settings[section][x]["type"] == "float": try: storedValue = self.settings[section][x]["value"] self.settings[section][x]["value"] = float(value) updated = True + # This test updates certain settings in webcontrol. Might be a bit hackis. + if storedValue != float(value): + self.processChange(self.settings[section][x]["key"],float(value)) + # If setting is a controller setting, then sync with controller if needed. if "firmwareKey" in self.settings[section][x]: self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], storedValue + self.settings[section][x]["firmwareKey"], storedValue, isImporting, ) + break except: - pass + break elif self.settings[section][x]["type"] == "int": try: storedValue = self.settings[section][x]["value"] self.settings[section][x]["value"] = int(value) updated = True + # This test updates certain settings in webcontrol. Might be a bit hackis. + if storedValue != int(value): + self.processChange(self.settings[section][x]["key"], int(value)) + # If setting is a controller setting, then sync with controller if needed. if "firmwareKey" in self.settings[section][x]: - if self.settings[section][x]["firmwareKey"] != 45: + #not sure why this test is here, probably legacy as the setting type for 85 is string. + if self.settings[section][x]["firmwareKey"] != 85: self.syncFirmwareKey( self.settings[section][x]["firmwareKey"], storedValue, + isImporting, ) + #added this because it appears to be missing. + break except: - pass + break elif self.settings[section][x]["type"] == "bool": try: + # change true/false to on/off if that's how it comes in to this function. I think this was + # done because forms come in as checkbox results (on/off) and webcontrol somewhere might want + # to set the value as true/false. if isinstance(value, bool): if value: value = "on" else: value = "off" - if value == "on": + if value == "on" or value == "1" or value == 1: storedValue = self.settings[section][x]["value"] self.settings[section][x]["value"] = 1 updated = True @@ -81,6 +263,7 @@ def setValue(self, section, key, value, recursionBreaker=False): self.syncFirmwareKey( self.settings[section][x]["firmwareKey"], storedValue, + isImporting, ) else: storedValue = self.settings[section][x]["value"] @@ -90,135 +273,74 @@ def setValue(self, section, key, value, recursionBreaker=False): self.syncFirmwareKey( self.settings[section][x]["firmwareKey"], storedValue, + isImporting, ) - + break except: - pass + break else: + # If not float, int, bool, then must be string. storedValue = self.settings[section][x]["value"] self.settings[section][x]["value"] = value + # This test updates certain settings in webcontrol. Might be a bit hackis. + if storedValue != value: + self.processChange(self.settings[section][x]["key"], value) updated = True if "firmwareKey" in self.settings[section][x]: self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], storedValue + self.settings[section][x]["firmwareKey"], storedValue, isImporting, ) + break if not found: - print("Did not find " + str(section) + ", " + str(key) + ", " + str(value)) + # I think SHOULDN'T be called any more. It was here previously because of how checkboxes were returned + # from forms (they aren't part of the form result if they aren't enabled). + if self.settings[section][x]["type"] == "bool": + self.data.console_queue.put(self.settings[section][x]["key"]) + storedValue = self.settings[section][x]["value"] + self.settings[section][x]["value"] = 0 + if "firmwareKey" in self.settings[section][x]: + self.syncFirmwareKey( + self.settings[section][x]["firmwareKey"], storedValue + ) + updated = True if updated: + # if not being updated from the computSettings, then call computeSettings to update if needed. if not recursionBreaker: self.computeSettings(None, None, None, True) - with open("webcontrol.json", "w") as outfile: + # and now save the settings to storage + with open(self.home+"/.WebControl/webcontrol.json", "w") as outfile: # print ("writing file") json.dump( self.settings, outfile, sort_keys=True, indent=4, ensure_ascii=False ) def updateSettings(self, section, result): - print("at update Settings") - updated = False + ''' + Take the form result, iterate through it and update the settings + :param section: The form's section (i.e., Advanced Settings) + :param result: the form's returned results. NOTE: disabled checkboxes are NOT returned in the results. + :return: + ''' + # Iterate through all the settings that SHOULD be in the form. for x in range(len(self.settings[section])): - # print(self.settings[section][x]["key"]) - # print(self.settings[section][x]["type"]) - found = False - for setting in result: - if self.settings[section][x]["key"] == setting: - - if self.settings[section][x]["type"] == "float": - try: - storedValue = self.settings[section][x]["value"] - self.settings[section][x]["value"] = float(result[setting]) - updated = True - if "firmwareKey" in self.settings[section][x]: - self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], - storedValue, - ) - except: - pass - elif self.settings[section][x]["type"] == "int": - try: - storedValue = self.settings[section][x]["value"] - self.settings[section][x]["value"] = int(result[setting]) - updated = True - if "firmwareKey" in self.settings[section][x]: - self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], - storedValue, - ) - except: - pass - elif self.settings[section][x]["type"] == "bool": - # print result[setting] - try: - if result[setting] == "on": - storedValue = self.settings[section][x]["value"] - self.settings[section][x]["value"] = 1 - updated = True - if "firmwareKey" in self.settings[section][x]: - # print "syncing1 true bool at:"+str(self.settings[section][x]['firmwareKey']) - self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], - storedValue, - ) - else: - storedValue = self.settings[section][x]["value"] - self.settings[section][x]["value"] = 0 - updated = True - if "firmwareKey" in self.settings[section][x]: - # print "syncing2 true bool at:"+str(self.settings[section][x]['firmwareKey']) - self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], - storedValue, - ) - except: - pass - - elif self.settings[section][x]["type"] == "options": - try: - # print(str(result[setting])) - storedValue = self.settings[section][x]["value"] - self.settings[section][x]["value"] = str(result[setting]) - # print(self.settings[section][x]["value"]) - updated = True - if "firmwareKey" in self.settings[section][x]: - self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], - storedValue, - ) - except: - pass - - else: - storedValue = self.settings[section][x]["value"] - self.settings[section][x]["value"] = result[setting] - updated = True - # print str(storedValue)+", "+str(result[settig]) - if "firmwareKey" in self.settings[section][x]: - # print "firmwareKey:"+str(self.settings[section][x]["firmwareKey"]) - self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], storedValue - ) - - # print setting+":"+str(result[setting])+"->"+str(settings[section][x]["value"]) - found = True - break - if not found: - # must be a turned off checkbox.. what a pain to figure out - if self.settings[section][x]["type"] == "bool": - storedValue = self.settings[section][x]["value"] - self.settings[section][x]["value"] = 0 - if "firmwareKey" in self.settings[section][x]: - # print "syncing3 false bool at:"+str(self.settings[section][x]['firmwareKey']) - self.syncFirmwareKey( - self.settings[section][x]["firmwareKey"], storedValue - ) - updated = True - if updated: - self.computeSettings(None, None, None, True) - with open("webcontrol.json", "w") as outfile: - json.dump( - self.settings, outfile, sort_keys=True, indent=4, ensure_ascii=False - ) + setting = self.settings[section][x]["key"] + # I think I put this here so that a disabled checkbox gets called as well. + # If the setting is not found in the results, then it must be a disabled checkbox and its value gets set + # to a zero. This probably should be cleaned up and resultValue set to "off" to make it jive with the + # tests in updateSetting. + if setting in result: + resultValue = result[setting] + else: + resultValue = 0 + #do a special check for comport because if its open, we need to close existing connection + if setting == "COMport": + currentSetting = self.data.config.getValue(section, setting) + if currentSetting != resultValue: + if self.data.connectionStatus == 1: + self.data.requestSerialClose = True + self.data.console_queue.put("closing serial connection") + self.setValue(section, setting, resultValue, recursionBreaker=False, isImporting = False) + self.data.console_queue.put("settings updated") def getJSONSettingSection(self, section): """ @@ -283,48 +405,97 @@ def getValue(self, section, key): break return ret - def syncFirmwareKey(self, firmwareKey, value, data=None): - # print "firmwareKey from sync:"+str(firmwareKey) - # print "value from sync:"+str(value) + def syncFirmwareKey(self, firmwareKey, value, isImporting=False, useStored=False, data=None): + ''' + :param firmwareKey: the firmwareKey value + :param value: the PREVIOUS value prior to updating. + :param isImporting: indicates to bypass syncing until all the importing of values is done. + :param useStored: indicates to use the value that's currently stored to update controller (holeyKinematics) + :param data: used by optical calibration to send function the error array to send to controller. (optical) + :return: + ''' for section in self.settings: for option in self.settings[section]: if "firmwareKey" in option and option["firmwareKey"] == firmwareKey: - # storedValue = self.get(section, option['key']) - storedValue = option["value"] - # print("firmwareKey:"+str(firmwareKey)+ " section:"+section+" storedValue:"+str(storedValue)+" value:"+str(value)) - if option["key"] == "spindleAutomate": - if storedValue == "Servo": - storedValue = 1 - elif storedValue == "Relay_High": - storedValue = 2 - elif storedValue == "Relay_Low": - storedValue = 3 - else: - storedValue = 0 - if value == "Servo": - value = 1 - elif value == "Relay_High": - value = 2 - elif value == "Relay_Low": - value = 3 + # if this is custom firmware OR if the setting is not custom, then do this. + if self.data.controllerFirmwareVersion > 100 or ("custom" not in option or option["custom"] != 1): + storedValue = option["value"] + # update storedValue based upon saved values.. TODO: fix this for comparison to value if broken. + if option["key"] == "spindleAutomate": + if storedValue == "Servo": + storedValue = 1 + elif storedValue == "Relay_High": + storedValue = 2 + elif storedValue == "Relay_Low": + storedValue = 3 + else: + storedValue = 0 + if value == "Servo": + value = 1 + elif value == "Relay_High": + value = 2 + elif value == "Relay_Low": + value = 3 + else: + value = 0 + # if error array, send by special function (optical) + if firmwareKey == 85: + if self.data.controllerFirmwareVersion >= 100: + self.data.console_queue.put("Sending error array") + if storedValue != "": + self.sendErrorArray(firmwareKey, storedValue, data) + # Can't recall why this is a pass and not a break.. might be legacy or related to + # the !="" check above. + pass + elif useStored is True: + # This probably could be moved to the last elif statement. Think this was here for + # troubleshooting purposes initially. TODO: verify and add 'or useStored' to last elif + strValue = self.firmwareKeyString(firmwareKey, storedValue) + app.data.gcode_queue.put(strValue) + # updates holeKinematics simulator model with new value. + self.data.holeyKinematics.updateSetting(firmwareKey, storedValue) + elif firmwareKey >= 87 and firmwareKey <= 98: + # Special test for sending curve fit coefficients (optical) + if self.data.controllerFirmwareVersion >= 100: + # Attempt at testing whether or not really small values are close by comparing % diff. + if not self.isPercentClose(float(storedValue), float(value)): + if not isImporting: + strValue = self.firmwareKeyString(firmwareKey, storedValue) + app.data.gcode_queue.put(strValue) + #not really needed since this is optical calibration section, but no harm. + self.data.holeyKinematics.updateSetting(firmwareKey, storedValue) + else: + break + elif not self.isClose(float(storedValue), float(value)) and not isImporting: + # Update the controller value if its different enough from previous value and + # we are not importing the groundcontrol.ini file. + strValue = self.firmwareKeyString(firmwareKey, storedValue) + app.data.gcode_queue.put(strValue) + # updates holeKinematics simulator model with new value. + self.data.holeyKinematics.updateSetting(firmwareKey, storedValue) else: - value = 0 - - # print str(firmwareKey)+": "+str(storedValue)+"?"+str(value) - if firmwareKey == 45: - # print "firmwareKey = 45" - # if storedValue != "": - # self.sendErrorArray(firmwareKey, storedValue, data) - pass - elif not self.isClose(float(storedValue), float(value)): - # print("firmwareKey(send) = "+ str(firmwareKey)+ ":"+ str(storedValue)) - app.data.gcode_queue.put( - "$" + str(firmwareKey) + "=" + str(storedValue) - ) - else: - break + break return + def isPercentClose(self, a, b, rel_tol = 0.0001): + ''' + Compares two numbers (really small or really large) and returns true if they are either really close + percent-wise (based on rel_tol) or, in the event b is zero, if is close by really small absolute difference. + If b=0, then there's a divide by zero error otherwise. + :param a: + :param b: + :param rel_tol: + :return: + ''' + if b != 0: + c = abs( abs(a/b) - 1.0) + if c < rel_tol: + return True + else: + return False + else: + return self.isClose(a, b) + def isClose(self, a, b, rel_tol=1e-06): """ Takes two values and returns true if values are close enough in value @@ -332,10 +503,17 @@ def isClose(self, a, b, rel_tol=1e-06): figure specified by rel_tol. Useful for comparing float values on arduino adapted from https://stackoverflow.com/a/33024979 """ - return abs(a - b) <= rel_tol * max(abs(a), abs(b)) + c = abs(a - b) <= rel_tol * max(abs(a), abs(b)) + return c def parseErrorArray(self, value, asFloat): - + ''' + Parses the error array that is stored in webcontrol.json and returns an array of either floats or integers. + Values are stored as integers that are equal to their original float value x 1000. + :param value: the error array + :param asFloat: iirc, used in optical calibration to get the numbers in float format rather than integers. + :return: + ''' # not the best programming, but I think it'll work xErrors = [[0 for x in range(15)] for y in range(31)] yErrors = [[0 for x in range(15)] for y in range(32)] @@ -386,9 +564,16 @@ def parseErrorArray(self, value, asFloat): return xFloatErrors, yFloatErrors def sendErrorArray(self, firmwareKey, value, data): - # parse out the array from string and then send them using the $O command - xErrors, yErrors = parseErrorArray(value, False) + ''' + :param firmwareKey: firmware key of controller's error array. + :param value: the value from settings + :param data: doesn't appear to be used, probably legacy. + :return: + ''' + # Get values in integer format + xErrors, yErrors = self.parseErrorArray(value, False) # now send the array: + # The '$O' triggers the firmware that this is an array coming in and to parse the values appropriately for x in range(0, 31): # 31 for y in range(0, 15): # 15 app.data.gcode_queue.put( @@ -402,7 +587,7 @@ def sendErrorArray(self, firmwareKey, value, data): + str(yErrors[x][y]) + " " ) - # if you send a 31,15 , it will trigger a save to EEPROM + # if you send a 31,15 , it will trigger a save to EEPROM. app.data.gcode_queue.put( "$O=" + str(31) + "," + str(15) + "," + str(42) + "," + str(42) + " " ) @@ -433,70 +618,38 @@ def parseFloat(self, text, position=0): return (None, position) def computeSettings(self, section, key, value, doAll=False): + ''' + Function was initially intended to recompute settings when needed, but currently all calls to this function + have doAll set to true, which causes all settings to be recomputed. + :param section: + :param key: + :param value: + :param doAll: Forces all settings to be recomputed. + :return: + ''' # Update Computed settings + if key == "loggingTimeout" or doAll is True: + loggingTimeout = self.getValue("WebControl Settings", "loggingTimeout") + + self.data.logger.setLoggingTimeout(loggingTimeout) if key == "kinematicsType" or doAll is True: if doAll is True: value = self.getValue("Advanced Settings", "kinematicsType") + currentValue = self.getValue("Computed Settings", "kinematicsTypeComputed") if value == "Quadrilateral": - self.setValue("Computed Settings", "kinematicsTypeComputed", "1", True) + if currentValue != "1": + self.setValue("Computed Settings", "kinematicsTypeComputed", "1", True) else: - self.setValue("Computed Settings", "kinematicsTypeComputed", "2", True) + if currentValue != "2": + self.setValue("Computed Settings", "kinematicsTypeComputed", "2", True) if key == "gearTeeth" or key == "chainPitch" or doAll is True: gearTeeth = float(self.getValue("Advanced Settings", "gearTeeth")) chainPitch = float(self.getValue("Advanced Settings", "chainPitch")) distPerRot = gearTeeth * chainPitch - self.setValue("Computed Settings", "distPerRot", str(distPerRot), True) - leftChainTolerance = float( - self.getValue("Advanced Settings", "leftChainTolerance") - ) - distPerRotLeftChainTolerance = (1 + leftChainTolerance / 100.0) * distPerRot - self.setValue( - "Computed Settings", - "distPerRotLeftChainTolerance", - str("{0:.5f}".format(distPerRotLeftChainTolerance)), - True, - ) - rightChainTolerance = float( - self.getValue("Advanced Settings", "rightChainTolerance") - ) - distPerRotRightChainTolerance = ( - 1 + rightChainTolerance / 100.0 - ) * distPerRot - self.setValue( - "Computed Settings", - "distPerRotRightChainTolerance", - str("{0:.5f}".format(distPerRotRightChainTolerance)), - True, - ) - - if key == "leftChainTolerance" or doAll: - distPerRot = float(self.getValue("Computed Settings", "distPerRot")) - leftChainTolerance = float( - self.getValue("Advanced Settings", "leftChainTolerance") - ) - distPerRotLeftChainTolerance = (1 + leftChainTolerance / 100.0) * distPerRot - self.setValue( - "Computed Settings", - "distPerRotLeftChainTolerance", - str("{0:.5f}".format(distPerRotLeftChainTolerance)), - True, - ) - - if key == "rightChainTolerance" or doAll is True: - distPerRot = float(self.getValue("Computed Settings", "distPerRot")) - rightChainTolerance = float( - self.getValue("Advanced Settings", "rightChainTolerance") - ) - distPerRotRightChainTolerance = ( - 1 + rightChainTolerance / 100.0 - ) * distPerRot - self.setValue( - "Computed Settings", - "distPerRotRightChainTolerance", - str("{0:.5f}".format(distPerRotRightChainTolerance)), - True, - ) + currentdistPerRot = self.getValue("Computed Settings", "distPerRot") + if currentdistPerRot != str(distPerRot): + self.setValue("Computed Settings", "distPerRot", str(distPerRot), True) if key == "enablePosPIDValues" or doAll is True: for key in ("KpPos", "KiPos", "KdPos", "propWeight"): @@ -504,14 +657,18 @@ def computeSettings(self, section, key, value, doAll=False): value = float(self.getValue("Advanced Settings", key)) else: value = self.getDefaultValue("Advanced Settings", key) - self.setValue("Computed Settings", key + "Main", value, True) + currentValue = self.getValue("Computed Settings", key + "Main") + if currentValue != value: + self.setValue("Computed Settings", key + "Main", value, True) # updated computed values for z-axis for key in ("KpPosZ", "KiPosZ", "KdPosZ", "propWeightZ"): if int(self.getValue("Advanced Settings", "enablePosPIDValues")) == 1: value = float(self.getValue("Advanced Settings", key)) else: value = self.getDefaultValue("Advanced Settings", key) - self.setValue("Computed Settings", key, value, True) + currentValue = self.getValue("Computed Settings", key) + if currentValue != value: + self.setValue("Computed Settings", key, value, True) if key == "enableVPIDValues" or doAll is True: for key in ("KpV", "KiV", "KdV"): @@ -519,28 +676,131 @@ def computeSettings(self, section, key, value, doAll=False): value = float(self.getValue("Advanced Settings", key)) else: value = self.getDefaultValue("Advanced Settings", key) - self.setValue("Computed Settings", key + "Main", value, True) + currentValue = self.getValue("Computed Settings", key + "Main") + if currentValue != value: + self.setValue("Computed Settings", key + "Main", value, True) # updated computed values for z-axis for key in ("KpVZ", "KiVZ", "KdVZ"): if int(self.getValue("Advanced Settings", "enablePosPIDValues")) == 1: value = float(self.getValue("Advanced Settings", key)) else: value = self.getDefaultValue("Advanced Settings", key) - self.setValue("Computed Settings", key, value, True) + currentValue = self.getValue("Computed Settings", key) + if currentValue != value: + self.setValue("Computed Settings", key, value, True) if key == "chainOverSprocket" or doAll is True: if doAll is True: value = self.getValue("Advanced Settings", "chainOverSprocket") - # print(value) + currentValue = self.getValue("Computed Settings","chainOverSprocketComputed") if value == "Top": - self.setValue("Computed Settings", "chainOverSprocketComputed", 1, True) + if currentValue != 1: + self.setValue("Computed Settings", "chainOverSprocketComputed", 1, True) elif value == "Bottom": - self.setValue("Computed Settings", "chainOverSprocketComputed", 2, True) + if currentValue != 2: + self.setValue("Computed Settings", "chainOverSprocketComputed", 2, True) + self.setValue("Computed Settings", "chainOverSprocketComputed", 2, True) if key == "fPWM" or doAll is True: + if doAll is True: + value = self.getValue("Advanced Settings", "fPWM") + currentValue = self.getValue("Computed Settings", "fPWMComputed") if value == "31,000Hz": - self.setValue("Computed Settings", "fPWMComputed", 1, True) + if currentValue != 1: + self.setValue("Computed Settings", "fPWMComputed", 1, True) elif value == "4,100Hz": - self.setValue("Computed Settings", "fPWMComputed", 2, True) + if currentValue != 2: + self.setValue("Computed Settings", "fPWMComputed", 2, True) + else: + if currentValue != 3: + self.setValue("Computed Settings", "fPWMComputed", 3, True) + + def parseFirmwareVersions(self): + ''' + Parses the files located in the installation's firmware directory for certain arduino firmwares (.hex files) + /madgrizzle is the optical calibration firmware + /holey is the holey calibration firmware + /maslowcnc is the stock firmware. + This function determines the version number. + :return: + ''' + home = "." + if hasattr(sys, '_MEIPASS'): + home = os.path.join(sys._MEIPASS) + print(self.home) + path = home+"/firmware/madgrizzle/*.hex" + for filename in glob.glob(path): + version = filename.split("-") + maxIndex = len(version)-1 + if maxIndex >= 0: + version = version[maxIndex].split(".hex") + self.data.customFirmwareVersion = version[0] + else: + self.data.customFirmwareVersion = "n/a" + path = home+"/firmware/maslowcnc/*.hex" + for filename in glob.glob(path): + version = filename.split("-") + maxIndex = len(version)-1 + if maxIndex >= 0: + version = version[maxIndex].split(".hex") + self.data.stockFirmwareVersion = version[0] + else: + self.data.stockFirmwareVersion = "n/a" + path = home+"/firmware/holey/*.hex" + for filename in glob.glob(path): + version = filename.split("-") + maxIndex = len(version)-1 + if maxIndex >= 0: + version = version[maxIndex].split(".hex") + self.data.holeyFirmwareVersion = version[0] else: - self.setValue("Computed Settings", "fPWMComputed", 3, True) + self.data.holeyFirmwareVersion = "n/a" + + def processChange(self, key, value): + ### TODO: This does not currently fire on bools ## + # Not really sure why I don't have it firing on bools.. must of had a reason + if key == "fps" or key == "videoSize" or key == "cameraSleep": + self.data.camera.changeSetting(key, value) + + + def firmwareKeyString(self, firmwareKey, value): + ''' + Processes firmwareKey and value into a gcode string to be sent to controller + :param firmwareKey: + :param value: + :return: + ''' + strValue = self.firmwareKeyValue(value) + gc = "$" + str(firmwareKey) + "=" + strValue + return gc + + def firmwareKeyValue(self, value): + ''' + Pulled in from holey calibration fork. Haven't really worked with it. + :param value: + :return: + ''' + try: + de = math.log(abs(value), 10) + ru = math.ceil(de) + except: + ru = 0 + fmt = '{:' + str(int(max(max(7 - ru, 7), abs(ru)))) + '.' + str(int(6 - ru)) + 'f}' + try: + return fmt.format(value) + except: + print('firmwareKeyString Exception: value = ' + str(value)) + return str(value) + + def reloadWebControlJSON(self): + ''' + Reloads the webcontrol.json file. This would be called after a restoral of the file. + :return: + ''' + try: + with open(self.home+"/.WebControl/webcontrol.json", "r") as infile: + self.settings = json.load(infile) + return True + except: + print("error reloading WebControlJSON") + return False diff --git a/webcontrol.json b/defaultwebcontrol.json similarity index 63% rename from webcontrol.json rename to defaultwebcontrol.json index b3286363..cdf60cfd 100644 --- a/webcontrol.json +++ b/defaultwebcontrol.json @@ -1,13 +1,22 @@ { "Advanced Settings": [ { - "default": 0.0, - "desc": "Max depth the z axis should plunge in order to find the touch probe\ndefault setting: 0.0", + "default": 0, + "desc": "Enable the use of a touch plate to allow for automatic setting of Z-Axis zero. DO NOT ENABLE UNLESS YOU HAVE A TOUCH PLATE!\ndefault setting: disabled", + "key": "touchPlate", + "section": "Advanced Settings", + "title": "Enable Use of Touch Plates", + "type": "bool", + "value": 0 + }, + { + "default": 10.0, + "desc": "Max depth in millimeters the z axis should plunge in order to find the touch probe\ndefault setting: 10 mm", "key": "maxTouchProbePlungeDistance", "section": "Advanced Settings", - "title": "Max touch Z-axis plunge", + "title": "Max Touch Z-axis Plunge", "type": "string", - "value": "0.0" + "value": "10" }, { "default": 8113.73, @@ -44,7 +53,8 @@ "section": "Advanced Settings", "title": "Chain Tolerance, Left Chain", "type": "string", - "value": "0.0" + "value": "0", + "firmwareKey": 40 }, { "default": 0, @@ -53,7 +63,18 @@ "section": "Advanced Settings", "title": "Chain Tolerance, Right Chain", "type": "string", - "value": "0.0" + "value": "0", + "firmwareKey": 41 + }, + { + "default": 5.1685e-6, + "desc": "Elasticity of the Chain [mm/mm/N]\ndefault setting: 5.1685e-6", + "key": "chainElasticity", + "section": "Advanced Settings", + "title": "Chain Elasticity", + "type": "float", + "value": 5.1685e-6, + "firmwareKey": 45 }, { "default": "Top", @@ -66,17 +87,17 @@ "section": "Advanced Settings", "title": "Top/Bottom Chain Feed", "type": "options", - "value": "Top" + "value": "Bottom" }, { - "default": 1650, + "default": 1651, "desc": "The length in mm that will be extended during chain calibration\ndefault setting: 1650", "firmwareKey": 11, "key": "chainExtendLength", "section": "Advanced Settings", "title": "Extend Chain Distance", "type": "string", - "value": "2032" + "value": "1651" }, { "default": 3360, @@ -86,7 +107,7 @@ "section": "Advanced Settings", "title": "Chain Length", "type": "string", - "value": "4267" + "value": "3360" }, { "default": 7560.0, @@ -131,7 +152,7 @@ "section": "Advanced Settings", "title": "Home Position X Coordinate", "type": "string", - "value": "-610.01" + "value": "0.0" }, { "default": 0.0, @@ -140,7 +161,7 @@ "section": "Advanced Settings", "title": "Home Position Y Coordinate", "type": "string", - "value": "-610.0" + "value": "0.0" }, { "default": 0, @@ -174,14 +195,14 @@ "value": "Triangular" }, { - "default": 140, + "default": 139.1, "desc": "The distance between where the chains attach and the center of the router bit in mm\ndefault setting: 140", "firmwareKey": 8, "key": "rotationRadius", "section": "Advanced Settings", "title": "Rotation Radius for Triangular Kinematics", "type": "string", - "value": "132.75" + "value": "139.1" }, { "default": 0, @@ -191,12 +212,12 @@ "section": "Advanced Settings", "title": "Chain Sag Correction Value for Triangular Kinematics", "type": "string", - "value": "33.00" + "value": "33" }, { "default": 0, "desc": "Enable modifying x,y coordinates during calculations to account for errors determined by optical calibration\ndefault setting: 0", - "firmwareKey": 44, + "firmwareKey": 144, "key": "enableOpticalCalibration", "section": "Advanced Settings", "title": "Use Calibration Error Matrix (Experimental)", @@ -206,7 +227,7 @@ { "default": 0, "desc": "Selects use interpolation of calibration error matrix or curve fit\ndefault setting: 0", - "firmwareKey": 46, + "firmwareKey": 86, "key": "useInterpolationOrCurve", "section": "Advanced Settings", "title": "Use Interpolation (True) or Curve Fit (False) (Experimental)", @@ -221,7 +242,7 @@ "section": "Advanced Settings", "title": "Top Beam Tilt (Experimental)", "type": "string", - "value": "0.0" + "value": "0" }, { "default": 0, @@ -311,7 +332,7 @@ "section": "Advanced Settings", "title": "Kp Velocity", "type": "string", - "value": "7" + "value": "5" }, { "default": 0, @@ -493,7 +514,7 @@ "firmwareKey": 38, "key": "chainOverSprocketComputed", "type": "string", - "value": 1 + "value": 2 }, { "firmwareKey": 39, @@ -501,41 +522,47 @@ "type": "string", "value": 3 }, - { - "firmwareKey": 40, - "key": "distPerRotLeftChainTolerance", - "type": "string", - "value": "63.50000" - }, - { - "firmwareKey": 41, - "key": "distPerRotRightChainTolerance", - "type": "string", - "value": "63.50000" - }, { "default": 1.0, "key": "distToMove", "type": "float", - "value": 24.0 + "value": 1.0 }, { - "default": 0.5, + "default": 0.1, "key": "distToMoveZ", "type": "float", - "value": 3.0 + "value": 0.1 }, { - "default": "MM", + "default": "INCHES", "key": "units", "type": "string", "value": "INCHES" }, { - "default": "MM", + "default": 0.02, + "key": "tolerance", + "type": "float", + "value": 0.02 + }, + { + "default": "INCHES", "key": "unitsZ", "type": "string", - "value": 3 + "value": "INCHES" + }, + { + "default": ".", + "key": "lastSelectedDirectory", + "type": "string", + "value": "." + }, + { + "default": ".", + "key": "lastSelectedBoardDirectory", + "type": "string", + "value": "." } ], "Maslow Settings": [ @@ -546,7 +573,7 @@ "section": "Maslow Settings", "title": "Serial Connection", "type": "string", - "value": "COM5" + "value": "" }, { "default": 2978.4, @@ -556,7 +583,7 @@ "section": "Maslow Settings", "title": "Distance Between Motors", "type": "string", - "value": "3581.481" + "value": "2978.4" }, { "default": 2438.4, @@ -586,7 +613,7 @@ "section": "Maslow Settings", "title": "Motor Offset Height in MM", "type": "string", - "value": "510" + "value": "463" }, { "default": 310, @@ -598,6 +625,16 @@ "type": "string", "value": "310" }, + { + "default": 97.9, + "desc": "Weight of sled [N].\ndefault setting: 97.9", + "firmwareKey": 46, + "key": "sledWeight", + "section": "Maslow Settings", + "title": "Sled Weight", + "type": "float", + "value": 97.9 + }, { "default": 139, "desc": "The vertical distance between where the chains mount on the sled to the cutting tool.\ndefault setting: 139", @@ -638,6 +675,31 @@ "type": "string", "value": "3.17" }, + { + "default": 0, + "desc": "Wii controller connected via Bluetooth?\ndefault setting: 0", + "key": "wiiPendantPresent", + "section": "Maslow Settings", + "title": "Wii Pendant Installed", + "type": "bool", + "value": 0 + }, + { + "default": 0, + "desc": "GPIO buttons run in separate process / system service", + "key": "MaslowButtonService", + "title": "Raspberry Pi Button Service Active", + "type": "bool", + "value": 0 + }, + { + "default": 0, + "desc": "Attached command line text display on Maslow", + "key": "clidisplay", + "title": "RPI Text display", + "type": "bool", + "value": 0 + }, { "default": "", "desc": "The path to the open file\\ndefault setting: your home directory", @@ -645,7 +707,7 @@ "section": "Maslow Settings", "title": "Open File", "type": "string", - "value": "C:\\Users\\john\\Desktop\\Maslow\\sled\\part.nc" + "value": "" }, { "default": "", @@ -654,7 +716,7 @@ "section": "Maslow Settings", "title": "Macro 1", "type": "string", - "value": "$$" + "value": "" }, { "default": "Macro 1", @@ -663,7 +725,7 @@ "section": "Maslow Settings", "title": "Macro 1 Title", "type": "string", - "value": "$$" + "value": "Macro 1" }, { "default": "", @@ -672,7 +734,7 @@ "section": "Maslow Settings", "title": "Macro 2", "type": "string", - "value": "B02 L1 R0" + "value": "" }, { "default": "Macro 2", @@ -681,7 +743,7 @@ "section": "Maslow Settings", "title": "Macro 2 Title", "type": "string", - "value": "B02 L1 R0" + "value": "Macro 2" }, { "default": 5, @@ -700,117 +762,126 @@ "title": "Buffer Gcode", "type": "bool", "value": 0 + }, + { + "default": "", + "desc": "The path to the open board file\\ndefault setting: your home directory", + "key": "openBoardFile", + "section": "Maslow Settings", + "title": "Open Board File", + "type": "string", + "value": "" } ], "Optical Calibration Settings": [ { "default": "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,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,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,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,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,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,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,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,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,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", - "firmwareKey": 45, + "firmwareKey": 85, "key": "xyErrorArray", "type": "string", - "value": "12903,12506,12414,12036,11804,11482,10993,10563,10964,10775,10417,9837,9775,9069,9316,9298,9134,8802,8439,7895,7763,7321,7229,6836,6378,6198,6092,5911,5782,5429,5031,13269,13014,12685,12296,11971,11768,11489,11313,10645,10689,10395,10388,9853,9785,9426,9461,9432,9134,8824,8404,8134,8032,7567,7437,6884,7144,6692,6809,6220,6069,5563,14045,13449,13408,12797,12663,12122,12107,11784,11572,11289,10726,10531,10289,10282,10418,10071,10053,9635,9396,9089,8745,8435,8395,8022,7919,7970,7502,7234,6740,6659,5987,14201,13489,13667,13170,12791,12579,11997,11947,11705,11348,11393,10835,10661,10431,10655,10313,10191,10055,9556,9531,9101,9073,9011,8727,8135,7959,7782,7682,7421,6918,6674,15003,14294,14592,13840,13423,13061,12970,12372,12302,12000,11895,11333,11488,11172,11379,11152,10935,10801,10463,10291,10036,9675,9614,9189,8766,9164,8819,8236,7868,7219,6748,15247,14653,14695,14172,13476,13209,12976,12650,12632,12467,12190,11810,11843,11506,11480,11116,11363,10708,10806,10298,10282,9808,9820,9396,9308,8773,9023,8329,8212,7521,7784,16329,15380,15469,14587,14685,14269,13633,13727,13304,13364,12959,12357,12579,12253,11973,12167,11894,11840,11749,11733,11036,10666,10688,10169,9746,10089,9628,9444,9300,8687,8661,15499,15528,15150,15417,15254,14626,14706,13598,13555,13181,12702,12617,12412,12356,12340,12328,12429,12176,11779,11754,11408,11347,11206,10585,10098,10117,9990,9663,8074,8099,7419,15574,15982,16617,16556,15145,15617,15360,14328,14597,13690,13463,13180,13492,12557,12575,12985,12887,12477,12475,12147,12045,12035,11473,11067,10510,10468,11015,10709,10029,9843,9161,18101,16510,16730,15680,15974,15182,15884,14673,15012,14955,14627,13787,13636,13655,13656,13142,13140,12971,11753,13410,12674,12524,11620,11308,11396,11544,11068,11191,10444,8857,8020,19049,18172,16825,15851,15924,15856,15836,15141,16594,14638,14215,14440,14381,13800,13828,13439,13077,13380,13505,13463,13095,12246,12302,12175,11252,12247,11368,11633,10438,10716,10664,19609,18179,16821,16457,16476,15831,15744,16216,16079,14686,15643,14696,15158,13578,14988,14824,14942,13811,13762,14126,12650,13338,13275,13127,11595,12820,11740,10525,10513,9135,10873,17646,17571,19053,18941,16914,16390,16434,15891,15995,16020,15064,15707,14748,15929,14652,15259,15115,14125,14035,13887,13885,14321,13840,13299,13071,12959,13127,12893,11138,12406,11969,17553,17527,18704,17593,17529,17982,17689,16297,16285,16245,16079,15745,14839,16064,15320,16040,15850,15616,14736,14600,14502,14332,13622,12899,12866,12488,12312,12532,12488,12453,11860,17568,20708,20745,18990,17585,18065,17614,16999,17014,17051,17753,16578,16537,16299,15752,15704,15963,15866,15651,14966,15070,14864,14490,14419,13905,13908,13930,12630,13734,13729,12977,2037,2975,3071,4139,4821,5554,5468,6247,5562,6984,8315,7427,8938,9812,8818,10119,9592,10605,10538,11613,10873,12065,11427,12125,12670,12481,12955,12880,12498,13252,13498,1414,2207,2557,3084,3718,4431,5539,4603,5509,5461,6269,6181,7455,7427,8090,7983,8896,9245,9263,9792,10063,10142,11419,10883,11367,11162,11695,11686,12011,12388,13032,2577,3078,3104,3493,4010,4145,4799,5337,4725,5815,5604,6628,7178,7746,7175,8112,8028,8305,8521,9211,9365,10181,10233,10263,10815,10718,11724,11685,12453,12354,13473,1877,2607,2474,2670,3063,3993,3615,4248,5505,4929,5631,6146,5664,6567,6374,7113,7038,7828,8314,8353,8805,8763,9615,9931,9926,10956,10988,11667,11666,12110,12845,2860,2858,2810,3494,3840,4342,4827,4744,5454,5073,5740,5836,6275,6877,6591,7295,6818,7794,7234,8106,8157,9041,9136,9805,10377,10393,11197,11530,12381,12462,13450,1841,2537,2576,2748,3073,3923,3860,4462,4482,5420,4738,5617,5779,5956,6498,6545,6438,7162,7185,7672,7610,8405,8369,9173,9290,10281,10424,11457,11521,12598,12850,2945,2713,2774,3088,4216,4120,4293,4417,4778,4754,5127,5227,5302,5749,5991,6254,6804,6290,7194,7122,7873,8397,8517,9362,9964,10211,11038,10680,11378,11794,11796,1942,2049,2401,3165,3497,4030,4037,4711,4718,4479,5142,5117,5276,6233,6251,6474,6535,6773,7396,7379,7124,8276,8523,8358,10192,10143,11065,11549,13049,13022,13686,1995,2778,3505,3443,3602,3716,4280,4284,4861,4896,4896,5051,5381,5437,5663,5379,6568,6049,6051,6521,7954,7927,8785,9314,9187,10595,10931,10739,11644,11865,12713,3567,2486,3506,3493,3059,3444,4220,4701,4656,4842,4973,5199,4830,4939,5027,6210,6206,6338,6688,7054,7791,7901,8134,8741,9021,10231,10234,10858,11591,13489,13312,3154,3057,2566,3443,3722,3878,4788,4592,4761,4687,4781,5602,5469,5090,6058,5845,6025,6022,6212,7127,7707,7895,7939,9162,9801,9557,11101,10725,12406,11750,11797,3679,3580,2696,3756,4016,3927,3859,4472,4594,4588,4864,5095,5231,5518,5452,5878,5891,6443,6439,6940,7414,7308,8511,8316,9468,9463,11249,12261,12247,12758,12914,2596,2636,4249,4128,4323,4219,4201,4716,5126,5120,5529,5255,5506,5324,5687,5949,5905,6199,6546,6692,6768,7567,8122,8920,8869,9572,10162,10734,12537,11972,12930,3046,3006,3525,3505,4485,4430,4760,5543,5604,5067,5298,6253,4615,5598,6006,6474,6486,6629,6522,7323,7199,8464,8800,10013,10011,10797,11247,12381,12447,12166,12967,3045,4851,4862,4741,4301,5025,4302,4939,4970,5010,5267,6557,6555,5764,6129,6098,5830,7003,6644,6399,6748,7344,7966,8470,9340,9303,11185,12442,11779,11784,13300" + "value": "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,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,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,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,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,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,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,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,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,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" }, { "default": "0", - "firmwareKey": 47, + "firmwareKey": 87, "key": "calX0", "type": "string", - "value": "12.306828365383796" + "value": "0" }, { "default": "0", - "firmwareKey": 48, + "firmwareKey": 88, "key": "calX1", "type": "string", - "value": "-0.0030334144723844995" + "value": "0" }, { "default": "0", - "firmwareKey": 49, + "firmwareKey": 89, "key": "calX2", "type": "string", - "value": "-0.006484037277598355" + "value": "0" }, { "default": "0", - "firmwareKey": 50, + "firmwareKey": 90, "key": "calX3", "type": "string", - "value": "-3.780558156344352e-07" + "value": "0" }, { "default": "0", - "firmwareKey": 51, + "firmwareKey": 91, "key": "calX4", "type": "string", - "value": "4.988530237200542e-08" + "value": "0" }, { "default": "0", - "firmwareKey": 52, + "firmwareKey": 92, "key": "calX5", "type": "string", - "value": "3.4616351643045745e-07" + "value": "0" }, { "default": "0", - "firmwareKey": 53, + "firmwareKey": 93, "key": "calY0", "type": "string", - "value": "6.2635116724449595" + "value": "0" }, { "default": "0", - "firmwareKey": 54, + "firmwareKey": 94, "key": "calY1", "type": "string", - "value": "0.004282628129145149" + "value": "0" }, { "default": "0", - "firmwareKey": 55, + "firmwareKey": 95, "key": "calY2", "type": "string", - "value": "0.0013022863069535669" + "value": "0" }, { "default": "0", - "firmwareKey": 56, + "firmwareKey": 96, "key": "calY3", "type": "string", - "value": "9.597606000766018e-07" + "value": "0" }, { "default": "0", - "firmwareKey": 57, + "firmwareKey": 97, "key": "calY4", "type": "string", - "value": "8.81047492386211e-07" + "value": "0" }, { "default": "0", - "firmwareKey": 58, + "firmwareKey": 98, "key": "calY5", "type": "string", - "value": "4.338345870544009e-06" + "value": "0" }, { "default": "0", "key": "opticalCenterX", "type": "string", - "value": "316.4" + "value": "0" }, { "default": "0", "key": "opticalCenterY", "type": "string", - "value": "213.9" + "value": "0" }, { "default": "1.0", "key": "scaleX", "type": "string", - "value": "1.028" + "value": "1.0" }, { "default": "1.0", @@ -843,45 +914,81 @@ "value": 0 }, { - "default": 12.7, + "default": 0.6, "key": "markerX", "type": "float", - "value": 15.24 + "value": 0.6 }, { - "default": 12.7, + "default": 0.6, "key": "markerY", "type": "float", - "value": 15.24 + "value": 0.6 + }, + { + "default": -15, + "key": "tlX", + "type": "int", + "value": -15 + }, + { + "default": 7, + "key": "tlY", + "type": "int", + "value": 7 + }, + { + "default": 15, + "key": "brX", + "type": "int", + "value": 15 + }, + { + "default": -7, + "key": "brY", + "type": "int", + "value": -7 + }, + { + "default": "Full Area", + "key": "calibrationExtents", + "type": "string", + "value": "Full Area" + } , + { + "default": 0.125, + "key": "positionTolerance", + "type": "float", + "value": 0.125 } ], "WebControl Settings": [ { "default": 0, - "desc": "When resizing the window, automatically reset the Gcode canvas to be centered and zoomed out. Program must be restarted to take effect.\ndefault setting: 0", - "key": "centerCanvasOnResize", + "desc": "When pressing the diagonal buttons in the main screen, use the distance to move as the total amount, not the amount for X and Y independently\ndefault setting: 0", + "key": "diagonalMove", "section": "WebControl Settings", - "title": "Center Canvas on Window Resize", + "title": "Diagonal Move Method", "type": "bool", - "value": 1 + "value": 0 }, { - "default": "pageup", - "desc": "Pressing this key will zoom in. Note combinations of keys like 'shift' + '=' may not work as expected. Program must be restarted to take effect.\ndefault setting: pageup", - "key": "zoomIn", + "default": 0, + "desc": "Enable on-screen reporting of actual sled position computed from chain lengths reported by controller. MAY CAUSE WEBCONTROL TO SLOW DOWN!\ndefault setting: disabled", + "key": "computedPosition", "section": "WebControl Settings", - "title": "Zoom In", - "type": "string", - "value": "pageup" + "title": "Computed Sled Position", + "type": "bool", + "value": 0 }, { - "default": "pagedown", - "desc": "Pressing this key will zoom in. Note combinations of keys like 'shift' + '=' may not work as expected. Program must be restarted to take effect.\ndefault setting: pagedown", - "key": "zoomOut", + "default": 0, + "desc": "Timeout logging after specified seconds of user and gcode processing activity, 0 value disables timeout\ndefault setting: 0", + "key": "loggingTimeout", "section": "WebControl Settings", - "title": "Zoom Out", - "type": "string", - "value": "pagedown" + "title": "Logger Idle Timeout", + "type": "float", + "value": 0 }, { "default": ".nc, .ngc, .text, .gcode", @@ -893,13 +1000,301 @@ "value": ".nc, .ngc, .text, .gcode" }, { - "default": ".45", - "desc": "Zoom scale for 'Reset View' command.\ndefault setting: .45", - "key": "viewScale", + "default": 0, + "desc": "Use 3D render with orbital controls in lieu of standard 2D rendering with pan/zoom\ndefault setting: False", + "key": "enable3D", "section": "WebControl Settings", - "title": "Reset View Scale", - "type": "string", - "value": ".45" + "title": "Enable 3D Display", + "type": "bool", + "value": 0 + }, + { + "default": 5000, + "desc": "Web interface Port Number used to access WebControl from browser. Requires restart to change.\ndefault setting: 5000", + "key": "webPort", + "section": "WebControl Settings", + "title": "Web Port Number", + "type": "int", + "value": 5000 + }, + { + "default": 0, + "desc": "Enable experimental releases to appear in release list\ndefault setting: No", + "key": "experimentalReleases", + "section": "WebControl Settings", + "title": "Enable Experimental Releases", + "type": "bool", + "value": 0 + } + ], + "Camera Settings": [ + { + "default": "640x480", + "desc": "Size of video image. Affects FPS and computational needs\ndefault setting: 640x480", + "key": "videoSize", + "options": [ + "640x480", + "1024x768" + ], + "section": "Camera Settings", + "title": "Video Image Size", + "type": "options", + "value": "640x480" + }, + { + "default": 5, + "desc": "Number of frames per second the camera captures\ndefault setting: 5", + "key": "fps", + "section": "Camera Settings", + "title": "fps", + "type": "float", + "value": 5 + }, + { + "default": 0.001, + "desc": "Sleep time (seconds) during camera thread. This is here to help us tweak the camera process\ndefault setting: 0.001", + "key": "cameraSleep", + "section": "Camera Settings", + "title": "Camera Thread Sleep Interval", + "type": "float", + "value": 0.001 } + ], + "GPIO Settings": [ + { + "default": "", + "desc": "GPIO2 functionality", + "key": "gpio2", + "section": "GPIO Settings", + "title": "GPIO2", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO3 functionality", + "key": "gpio3", + "section": "GPIO Settings", + "title": "GPIO3", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO4 functionality", + "key": "gpio4", + "section": "GPIO Settings", + "title": "GPIO4", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO5 functionality", + "key": "gpio5", + "section": "GPIO Settings", + "title": "GPIO5", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO6 functionality", + "key": "gpio6", + "section": "GPIO Settings", + "title": "GPIO6", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO7 functionality", + "key": "gpio7", + "section": "GPIO Settings", + "title": "GPIO7", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO8 functionality", + "key": "gpio8", + "section": "GPIO Settings", + "title": "GPIO8", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO9 functionality", + "key": "gpio9", + "section": "GPIO Settings", + "title": "GPIO9", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO10 functionality", + "key": "gpio10", + "section": "GPIO Settings", + "title": "GPIO10", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO11 functionality", + "key": "gpio11", + "section": "GPIO Settings", + "title": "GPIO11", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO12 functionality", + "key": "gpio12", + "section": "GPIO Settings", + "title": "GPIO12", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO13 functionality", + "key": "gpio13", + "section": "GPIO Settings", + "title": "GPIO13", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO14 functionality", + "key": "gpio14", + "section": "GPIO Settings", + "title": "GPIO14", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO15 functionality", + "key": "gpio15", + "section": "GPIO Settings", + "title": "GPIO15", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO16 functionality", + "key": "gpio16", + "section": "GPIO Settings", + "title": "GPIO16", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO17 functionality", + "key": "gpio17", + "section": "GPIO Settings", + "title": "GPIO17", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO18 functionality", + "key": "gpio18", + "section": "GPIO Settings", + "title": "GPIO18", + "type": "options", + "value": "" + } , + { + "default": "", + "desc": "GPIO19 functionality", + "key": "gpio19", + "section": "GPIO Settings", + "title": "GPIO19", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO20 functionality", + "key": "gpio20", + "section": "GPIO Settings", + "title": "GPIO20", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO21 functionality", + "key": "gpio21", + "section": "GPIO Settings", + "title": "GPIO21", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO22 functionality", + "key": "gpio22", + "section": "GPIO Settings", + "title": "GPIO22", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO23 functionality", + "key": "gpio23", + "section": "GPIO Settings", + "title": "GPIO23", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO24 functionality", + "key": "gpio24", + "section": "GPIO Settings", + "title": "GPIO24", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO25 functionality", + "key": "gpio25", + "section": "GPIO Settings", + "title": "GPIO25", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO26 functionality", + "key": "gpio26", + "section": "GPIO Settings", + "title": "GPIO26", + "type": "options", + "value": "" + }, + { + "default": "", + "desc": "GPIO27 functionality", + "key": "gpio27", + "section": "GPIO Settings", + "title": "GPIO27", + "type": "options", + "value": "" + } + ] } \ No newline at end of file diff --git a/docs/Actions/Calibration-Setup/Screenshot.png b/docs/Actions/Calibration-Setup/Screenshot.png new file mode 100644 index 00000000..00362eaa Binary files /dev/null and b/docs/Actions/Calibration-Setup/Screenshot.png differ diff --git a/docs/Actions/Calibration-Setup/checkForChainSkip.md b/docs/Actions/Calibration-Setup/checkForChainSkip.md new file mode 100644 index 00000000..6363a9d5 --- /dev/null +++ b/docs/Actions/Calibration-Setup/checkForChainSkip.md @@ -0,0 +1,32 @@ +--- +layout: default +title: Check for Chain Skip +nav_order: 9 +parent: Calibration / Setup +grand_parent: Actions +WCVersion: 0.916 +--- +# Check for Chain Skip + +Release: >0.906 +{: .label .label-blue } + +### Description +This function allows you to test whether one (or both) of your chains have skipped on the sprocket. The use of this function requires that you have marked the chain link that was on the top tooth of the sprocket after you extended the chains to connect them to the sled. + +See: [Set Sprockets & Reset Chains]({{ site.baseurl }}{% link Actions/Calibration-Setup/setSprocketsVertical.md %}) + +### Process + +The sled will be moved such that the length of each chain equals the 'Extend Chain Distance' (found in Advanced Settings). If you marked the chain link on the top tooth of the sprocket when you set/reset your chain lengths, this chain link should be on the top tooth. If the link is not, then your chain has skipped a tooth... or more. + +![Sprocket with Marked Link at Top](../../assets/Actions/Calibration-Setup/markedLinkAtTop.png) + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|Marked link is NOT on top tooth. |You chain has skipped. You need to reset chain lengths and look for solutions to prevent further chain skips. Check the alignment of the motors and the sled to make sure they are all in the same plane. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Calibration-Setup/holeyCalibration.md b/docs/Actions/Calibration-Setup/holeyCalibration.md new file mode 100644 index 00000000..87f0744a --- /dev/null +++ b/docs/Actions/Calibration-Setup/holeyCalibration.md @@ -0,0 +1,47 @@ +--- +layout: default +title: Holey Calibration +nav_order: 7 +parent: Calibration / Setup +grand_parent: Actions +WCVersion: 0.915 +--- +# Holey Calibration + +Release: >0.906 +{: .label .label-blue } + +If you are using holey calibration firmware, use 'Actions->Holey Calibration' to calibrate. If using stock firmware, go here: + +[Triangular Calibration]({{ site.baseurl }}{% link Actions/Calibration-Setup/triangularCalibration.md %}) + +### Step 1: Cut Pattern + +Press 'Cut Calibration Pattern' and wait for the sled to complete the cutting. + +![Cut Pattern](../../assets/holeyCalibration/cutPattern.png) + + +### Step 2: Measure + +Make and record your measurements as requested. Double check and triple check them.. seriously.. do it. + +![Enter Measurements](../../assets/holeyCalibration/measurements.png) + + +### Step 3: Enter Measurements + +Enter the measurements and double and triple check you entered them correctly and in the correct units. If so, press 'Calculate' + +![Enter Measurements](../../assets/holeyCalibration/calculate.png) + + +### Step 4: Accept Results + +If all looks good, press 'Accept Results' (you may have to scroll down the screen to see it)| + +![Enter Measurements](../../assets/holeyCalibration/acceptResults.png) + +### Step 5: Dance a Jig + +You're calibrated! Note, calibration can be an iterative process and some have found improvements in their Maslow's accuracy by calibrating a second time. Make sure to recut the test pattern if you chose to calibrate again. diff --git a/docs/Actions/Calibration-Setup/importGroundControlini.md b/docs/Actions/Calibration-Setup/importGroundControlini.md new file mode 100644 index 00000000..55644d13 --- /dev/null +++ b/docs/Actions/Calibration-Setup/importGroundControlini.md @@ -0,0 +1,30 @@ +--- +layout: default +title: Import groundcontrol.ini File +nav_order: 1 +parent: Calibration / Setup +grand_parent: Actions +WCVersion: 0.916 +--- +# Import groundcontrol.ini File + +Release: >0.906 +{: .label .label-blue } + +### Description +This function allows the user to import an existing groundcontrol.ini file to update WebControl's settings. + +### Process + +If the user is moving from using Ground Control to WebControl, the user may import an existing groundcontrol.ini file into WebControl. Upon starting WebControl for the first time, a message will be presented to the user to advise them to perform this operation. + +Pressing the 'Import groundcontrol.ini File' button will result in WebControl requesting that the user to upload a groundcontrol.ini file. WebControl will parse the file and update matched settings contained within the webcontrol.json settings file. Upon conclusion of the update, WebControl will sync the settings with the controller. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Calibration-Setup/importWebcontroljson.md b/docs/Actions/Calibration-Setup/importWebcontroljson.md new file mode 100644 index 00000000..3ec181a2 --- /dev/null +++ b/docs/Actions/Calibration-Setup/importWebcontroljson.md @@ -0,0 +1,28 @@ +--- +layout: default +title: Import webcontrol.json File +nav_order: 2 +parent: Calibration / Setup +grand_parent: Actions +WCVersion: 0.916 +--- +# Import webcontrol.json File + +Release: >0.906 +{: .label .label-blue } + +### Description +This function allows the user to import an existing webcontrol.json file to update WebControl's settings. + +### Process + +Pressing the 'Import webcontrol.json File' button will result in WebControl requesting that the user to upload an existing webcontrol.json file. WebControl will parse the file and update matched settings contained within the webcontrol.json settings file. Settings found in the new webcontrol.json file but not in the old webcontrol.json file will be added. Upon conclusion of the update, WebControl will sync the settings with the controller. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Calibration-Setup/index.md b/docs/Actions/Calibration-Setup/index.md new file mode 100644 index 00000000..c9906560 --- /dev/null +++ b/docs/Actions/Calibration-Setup/index.md @@ -0,0 +1,11 @@ +--- +layout: default +title: Calibration / Setup +nav_order: 2 +has_children: true +parent: Actions +--- +# Calibration/Setup + +Release: >0.906 +{: .label .label-blue } diff --git a/docs/Actions/Calibration-Setup/quickConfigure.md b/docs/Actions/Calibration-Setup/quickConfigure.md new file mode 100644 index 00000000..afaf3613 --- /dev/null +++ b/docs/Actions/Calibration-Setup/quickConfigure.md @@ -0,0 +1,35 @@ +--- +layout: default +title: Quick Configure +nav_order: 3 +parent: Calibration / Setup +grand_parent: Actions +WCVersion: 0.916 +--- +# Quick Configure + +Release: >0.906 +{: .label .label-blue } + +### Description +This 'guide' is designed to assist the user with initially configuring WebControl with specific parameters to allow for the calibration process to be successfully completed. + +### Process + +In order to successfully complete the calibration process, WebControl needs to know a few specific parameters so that when the calibration pattern can be cut successfully. These values are specific to the design of the Maslow the user has opted to build: + +* Kinematics Kit Type +* Chain Around Sprocket Type +* Distance Between Motors +* Height of Motors Above Workspace + +The 'Quick Configure' function guides the user as to how to determine and enter the required information to set these parameters. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Calibration-Setup/returnToCenter.md b/docs/Actions/Calibration-Setup/returnToCenter.md new file mode 100644 index 00000000..bf48dd93 --- /dev/null +++ b/docs/Actions/Calibration-Setup/returnToCenter.md @@ -0,0 +1,40 @@ +--- +layout: default +title: Return to Center +nav_order: 8 +parent: Calibration / Setup +grand_parent: Actions +WCVersion: 0.916 +--- +# Return to Center + +Release: >0.906 +{: .label .label-blue } + +### Description +This function instructs WebControl to send a command to the controller to return the sled to center of the work area. + +### Process + +WebControl places the controller in absolute position mode by sending: + +`G90` + +WebControl instructs the controller to raise the Z-axis to the 'safe height' (Maslow Settings -> Z-Axis Safe Travel Height in MM) + +`G00 Zxx` + +where xx is the value for the safe height. + +Maslow instructs the controller to move to the center of the work area (i.e., 0,0) + +`G00 X0.0, Y0.0` + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Calibration-Setup/setSprocketsVertical.md b/docs/Actions/Calibration-Setup/setSprocketsVertical.md new file mode 100644 index 00000000..b3aa21ea --- /dev/null +++ b/docs/Actions/Calibration-Setup/setSprocketsVertical.md @@ -0,0 +1,88 @@ +--- +layout: default +title: Set Sprockets & Reset Chains +nav_order: 4 +parent: Calibration / Setup +grand_parent: Actions +WCVersion: 0.916 +--- +# Set Sprockets & Reset Chains + +Release: >0.906 +{: .label .label-blue } + +### Description +This function allows the user to reset chain chains by setting a tooth on each sprocket vertical, installing the chains on the teeth, and extending the chains a specific distance to allow the chains to be attached to the sled. + + +### Process +The process of resetting the chains involves two steps; first, each sprocket has one tooth placed as perfectly vertical as possible and then, second, the chains are extended by a specific length. + +If the user follows these directions the first time they set the chain lengths, future chain lengths can be done quicker using the optional Quick Way. + +#### The Long Way #### + +If this the the first time setting the chains, then you will need to do it the long way. + +Step 1) Set left sprocket vertical. Use the clockwise/counterclockwise buttons to rotate the sprocket (Button Set 1). + +Step 2) Repeat for right sprocket (Button Set 2). + +![Sprocket with Vertical Tooth](../../assets/gettingStarted/Sprocket%20at%2012-00.png) + +_Sprocket with Vertical Tooth_ + +Step 3) Press 'Define Zero' (Button 4). + +Step 4) Install Chains. Install the chains on the sprocket such that the first link is resting on the top sprocket tooth. The placement depends on if you built the frame for 'Chains Off Top' or 'Chains Off Bottom' + +![Chains Off Bottom](../../assets/gettingStarted/chainOffSprocketsBottom.png) + +_Chains Off Bottom_ + +![Chains Off Top](../../assets/gettingStarted/chainOffSprocketsTop.png) + +_Chains Off Top_ + +Step 5) Extend Left Chain. Press ‘Extend Left Chain to xxxx mm’ (Button 5). Warning: This is one spot where the chains can get wrapped around the sprocket. Grab hold of the end of the chain and apply tension to it as it feeds off the sprocket so it doesn’t wrap. + +Step 6) Extend Right Chain. Press ‘Extend Right Chain to xxxx mm’ (Button 6). Warning: Same as above. + +Step 7) Connect Sled. Connect up your sled to the extended chains. + +Step 8) Mark chains. This step is to allow you to use the Quick Way of resetting the chains. Take a marker, nail polish, something, and mark the specific chain link that is on top of the top tooth. If the ‘Extend Chain Distance’ is a multiple of 6.35 mm, there should be a tooth perfectly vertical after extending the chains. Mark this because if you ever have to reset the chains, you need to know which link is this one. + +Your chains are now reset! **Note: It is unlikely that your sled is in the center of the board. It should be centered horizontally, but likely is not centered vertically. That's ok. The machine knows where its at and if you look at the main screen, the red reticle should show the sled to be where it is actually located. If not, then something went wrong.** + +#### The Quick Way #### + +If you perfomed Step 8 above when you first set your chains, you know which link was on the vertical tooth of each motor when the chains were extended to a specific distance. Because of this, all you need to do to reset the chain lengths is to set a tooth of each sprocket vertical, reapply the marked link back onto that tooth, and tell the machine the chains are reset... + +Step 1) Set left sprocket vertical. + +Step 2) Repeat for right sprocket. + +Step 3) Install Chains. Place the chain link that's been marked back on the top tooth of each motor. + +Step 4) Connect Sled. Connect up your sled to the extended chains. + +Step 5) Press 'Manually Set Chains At xxxx mm' (Button 8). This tells the controller that the chains are extended a distance of xxxx mm (where xxxx is the Extend Chain Length setting). The controller now knows the lengths of the chains and therefore the position of the sled. + +Your chains are now reset! **Note: To repeat the note above, it is unlikely that your sled is in the center of the board. It should be centered horizontally, but likely is not centered vertically. That's ok. The machine knows where its at and if you look at the main screen, the red reticle should show the sled to be where it is actually located. If not, then something went wrong.** + +### Automatic ### + +So, what's up with the 'Automatic' button (Button 3*)? This button is intended to return one of the sprockets teeth to vertical. This function was available in ground control, but the odd thing is that normally when you are trying to set your sprockets vertical, it's because the controller doesn't know the chain lengths and therefore doesn't know the sprockets position. So pushing this button will NOT likely result in a tooth vertical. + +However, during testing and development of Maslow, this capability did prove handy, so it's here as well. It will probably will go away or be moved elsewhere. + +### Troubleshooting + +**TBD** + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Calibration-Setup/triangularCalibration.md b/docs/Actions/Calibration-Setup/triangularCalibration.md new file mode 100644 index 00000000..3282110f --- /dev/null +++ b/docs/Actions/Calibration-Setup/triangularCalibration.md @@ -0,0 +1,47 @@ +--- +layout: default +title: Triangular Calibration +nav_order: 5 +parent: Calibration / Setup +grand_parent: Actions +WCVersion: 0.915 +--- +# Triangular Calibration + +Release: >0.906 +{: .label .label-blue } + +If you are using stock firmware, use 'Actions->Holey Calibration' to calibrate. If using holey calibration firmware, go here: + +[Holey Calibration]({{ site.baseurl }}{% link Actions/Calibration-Setup/holeyCalibration.md %}) + +### Step 1: Cut Pattern + +Press 'Cut Calibration Pattern' and wait for the sled to complete the cutting. + +![Cut Pattern](../../assets/triangularCalibration/cutPattern.png) + + +### Step 2: Measure + +Make and record your measurements as requested. Double check and triple check them.. seriously.. do it. + +![Enter Measurements](../../assets/triangularCalibration/measurements.png) + + +### Step 3: Enter Measurements + +Enter the measurements and double and triple check you entered them correctly and in the correct units. If so, press 'Calculate' + +![Enter Measurements](../../assets/triangularCalibration/calculate.png) + + +### Step 4: Accept Results + +If all looks good, press 'Accept Results' (you may have to scroll down the screen to see it)| + +![Enter Measurements](../../assets/triangularCalibration/acceptResults.png) + +### Step 5: Dance a Jig + +You're calibrated! Note, calibration can be an iterative process and some have found improvements in their Maslow's accuracy by calibrating a second time. Make sure to recut the test pattern if you chose to calibrate again. diff --git a/docs/Actions/Controller/index.md b/docs/Actions/Controller/index.md new file mode 100644 index 00000000..5e330066 --- /dev/null +++ b/docs/Actions/Controller/index.md @@ -0,0 +1,11 @@ +--- +layout: default +title: Controller +nav_order: 1 +has_children: true +parent: Actions +--- +# Controller + +Release: >0.906 +{: .label .label-blue } diff --git a/docs/Actions/Controller/syncSettings.md b/docs/Actions/Controller/syncSettings.md new file mode 100644 index 00000000..ebada617 --- /dev/null +++ b/docs/Actions/Controller/syncSettings.md @@ -0,0 +1,32 @@ +--- +layout: default +title: Sync Settings +nav_order: 4 +parent: Controller +grand_parent: Actions +--- +# Sync Settings + +Release: >0.906 +{: .label .label-blue } + + +### Description +This function sends a command to the controller to return each of its settings. Upon receiving the setting, WebControl compares the setting's value and if different than what WebControl has in its settings, WebControl sends a setting update to the controller. + +### Process + +The process for syncing settings (based upon current stock firmware as of 11/27/19) is as follows: + +* A special gcode command ($$) is sent to the controller +* Controller reports each firmware setting's key and value in the $x=y format, where 'x' is the firmware setting's key and 'y' is the value. +* WebControl compares the received setting value with the one in its memory. +* If the two settings are not equal or not really, really close to each other, WebControl sends the setting value to the controller in the $x=y format. + +### Notes + +"Really, really close" is roughly defined as a difference so small that it would have no impact on the performance of the controller if the old setting was used. For example, if distance between motors in the firmware is 3000.0000 mm and in WebControl its 3000.0001 mm, the setting will not be updated because its "really, really close" + +The routine to determine if the values are really, really close needs some work when dealing with really, really small numbers. It's possible (or likely) that you might see a setting update for something like "Chain Elasticity" everytime the controller and WebControl syncs. Don't Panic. It's fine. + + diff --git a/docs/Actions/Controller/upgradeCustomFirmware.md b/docs/Actions/Controller/upgradeCustomFirmware.md new file mode 100644 index 00000000..c6af1485 --- /dev/null +++ b/docs/Actions/Controller/upgradeCustomFirmware.md @@ -0,0 +1,34 @@ +--- +layout: default +title: Upgrade Custom Firmware +nav_order: 3 +parent: Controller +grand_parent: Actions +--- +# Upgrade Custom Firmware + +Release: >0.906 +{: .label .label-blue } + + +### Description +This function upgrades the controller firmware with the 'custom' firmware included in the WebControl release. This is highly experimental and not recommended for anyone to attempt to use... except for madgrizzle.. it's what he uses to experiment. When running custom firmware, 'Optical Calibration' is enabled. + +### Process + +The process for upgrading the custom firmware (based upon current stock firmware as of 11/27/19) is as follows: + +* WebControl closes the serial connection to the controller and pauses trying to reconnect. +* WebControls calls a system command to update the controller firmware. +* After the system command returns, the connection to the controller is reestablished. + +### Technical Details + +To update the firmware, WebControl uses the os.system() command to call 'avrdude' to upgrade the firmware. avrdude is included in the release in the tools directory. Each release contains a version that is compatible with the release's operating system, however, the linux version is based upon Ubuntu and may not work on other linux distributions. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | \ No newline at end of file diff --git a/docs/Actions/Controller/upgradeHoleyFirmware.md b/docs/Actions/Controller/upgradeHoleyFirmware.md new file mode 100644 index 00000000..194b5eaa --- /dev/null +++ b/docs/Actions/Controller/upgradeHoleyFirmware.md @@ -0,0 +1,34 @@ +--- +layout: default +title: Upgrade Holey Firmware +nav_order: 2 +parent: Controller +grand_parent: Actions +--- +# Upgrade Holey Firmware + +Release: >0.906 +{: .label .label-blue } + + +### Description +This function upgrades the controller firmware with the 'holey calibration' firmware included in the WebControl release. When running holey firmware, 'Holey Calibration' is enabled. + +### Process + +The process for upgrading the holey firmware (based upon current stock firmware as of 11/27/19) is as follows: + +* WebControl closes the serial connection to the controller and pauses trying to reconnect. +* WebControls calls a system command to update the controller firmware. +* After the system command returns, the connection to the controller is reestablished. + +### Technical Details + +To update the firmware, WebControl uses the os.system() command to call 'avrdude' to upgrade the firmware. avrdude is included in the release in the tools directory. Each release contains a version that is compatible with the release's operating system, however, the linux version is based upon Ubuntu and may not work on other linux distributions. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | \ No newline at end of file diff --git a/docs/Actions/Controller/upgradeStockFirmware.md b/docs/Actions/Controller/upgradeStockFirmware.md new file mode 100644 index 00000000..ecf89edd --- /dev/null +++ b/docs/Actions/Controller/upgradeStockFirmware.md @@ -0,0 +1,34 @@ +--- +layout: default +title: Upgrade Stock Firmware +nav_order: 1 +parent: Controller +grand_parent: Actions +--- +# Upgrade Stock Firmware + +Release: >0.906 +{: .label .label-blue } + + +### Description +This function upgrades the controller firmware with the 'stock' firmware included in the WebControl release. When running stock firmware, only 'Triangular Calibration' is enabled. + +### Process + +The process for upgrading the stock firmware (based upon current stock firmware as of 11/27/19) is as follows: + +* WebControl closes the serial connection to the controller and pauses trying to reconnect. +* WebControls calls a system command to update the controller firmware. +* After the system command returns, the connection to the controller is reestablished. + +### Technical Details + +To update the firmware, WebControl uses the os.system() command to call 'avrdude' to upgrade the firmware. avrdude is included in the release in the tools directory. Each release contains a version that is compatible with the release's operating system, however, the linux version is based upon Ubuntu and may not work on other linux distributions. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | \ No newline at end of file diff --git a/docs/Actions/Controller/wipeControllerEEPROM.md b/docs/Actions/Controller/wipeControllerEEPROM.md new file mode 100644 index 00000000..4605c720 --- /dev/null +++ b/docs/Actions/Controller/wipeControllerEEPROM.md @@ -0,0 +1,30 @@ +--- +layout: default +title: Wipe Controller EEPROM +nav_order: 7 +parent: Controller +grand_parent: Actions +--- +# Wipe Controller EEPROM + +Release: >0.918 +{: .label .label-blue } + + +### Description +This function sends a command to the controller to fully wipe the EEPROM, including the positional data and the firmware settings. This function is intended to restore the EEPROM back to original clean condition. + +### Process + +The process for wiping the EEPROM based upon current stock firmware as of 11/27/19) is as follows: + +* A special gcode command ($RST=*) is sent to the controller +* Controller writes a 0 value to the entire EEPROM memory space. This will delete all positional data and settings as well as FAKE_SERVO settings. +* Controller will reset after completed. + +New to 0.918 + +* WebControl will wait for two seconds and then send a settings sync command ($$) to resend WebControl's settings to the controller. +* WebControl will send a command to the controller (B04) to set the chain lengths equal to the 'Extend Chain Distance' in Advanced Settings + + diff --git a/docs/Actions/Controller/wipeControllerPositionAndSettings.md b/docs/Actions/Controller/wipeControllerPositionAndSettings.md new file mode 100644 index 00000000..0cfad243 --- /dev/null +++ b/docs/Actions/Controller/wipeControllerPositionAndSettings.md @@ -0,0 +1,30 @@ +--- +layout: default +title: Wipe Controller Position & Settings +nav_order: 6 +parent: Controller +grand_parent: Actions +--- +# Wipe Controller Position & Settings + +Release: >0.918 +{: .label .label-blue } + + +### Description +This function sends a command to the controller to reinitialize the positional data and the firmware settings. + +### Process + +The process for wiping the controller positional data (i.e., chain lengths) and settings (based upon current stock firmware as of 11/27/19) is as follows: + +* A special gcode command ($RST=#) is sent to the controller +* Controller writes a 0 value to EEPROM bytes associated with the positional data and the settings storage area. +* Controller will reset after completed. + +New to 0.918 + +* WebControl will wait for two seconds and then send a settings sync command ($$) to resend WebControl's settings to the controller. +* WebControl will send a command to the controller (B04) to set the chain lengths equal to the 'Extend Chain Distance' in Advanced Settings + + diff --git a/docs/Actions/Controller/wipeControllerSettings.md b/docs/Actions/Controller/wipeControllerSettings.md new file mode 100644 index 00000000..24995408 --- /dev/null +++ b/docs/Actions/Controller/wipeControllerSettings.md @@ -0,0 +1,29 @@ +--- +layout: default +title: Wipe Controller Settings +nav_order: 5 +parent: Controller +grand_parent: Actions +--- +# Wipe Controller Settings + +Release: >0.918 +{: .label .label-blue } + + +### Description +This function sends a command to the controller to reinitialize the firmware settings. + +### Process + +The process for wiping the controller settings (based upon current stock firmware as of 11/27/19) is as follows: + +* A special gcode command ($RST=$) is sent to the controller +* Controller writes a 0 value to EEPROM bytes associated with the settings storage area. +* Controller will reset after completed. + +New to 0.918 + +* WebControl will wait for two seconds and then send a settings sync command ($$) to resend WebControl's settings to the controller. + + diff --git a/docs/Actions/Diagnostics-Maintenance/backupWebControl.md b/docs/Actions/Diagnostics-Maintenance/backupWebControl.md new file mode 100644 index 00000000..73ad4110 --- /dev/null +++ b/docs/Actions/Diagnostics-Maintenance/backupWebControl.md @@ -0,0 +1,43 @@ +--- +layout: default +title: Backup WebControl +nav_order: 4 +parent: Diagnostics / Maintenance +grand_parent: Actions +WCVersion: 0.917 +--- +# Backup WebControl + +Release: >0.917 +{: .label .label-blue } + +### Description + +This function allows you to download a backup copy of your .WebControl directory. + +### Process + +Pressing the 'Backup WebControl' will instruct WebControl to create a zip file of the .WebControl directory containing all information specific to your installation of WebControl. This includes the following: + +* Uploaded GCode files +* Board Management Files +* webcontrol.json +* log.txt +* alog.txt +* Imported files (like groundcontrol.ini) +* Downloaded upgrade files (see note below) + +The file will be named 'wc_backup_XXXXX-YYYYY.zip' where XXXXXX is the data in YYMMDD format and YYYYYY is the time in HHMMSS format. + +After creating the zip file, WebControl will send the file to the browser for the user to download. + +**Note:** The backup file will also contain a copy of all the release versions to which you have upgraded. The release files are rather large (~70 MB) so the backup file will grow to be pretty large. A near-future release will delete the old files after an upgrade is complete so this won't become an issue. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Diagnostics-Maintenance/clearLogFiles.md b/docs/Actions/Diagnostics-Maintenance/clearLogFiles.md new file mode 100644 index 00000000..16e071a0 --- /dev/null +++ b/docs/Actions/Diagnostics-Maintenance/clearLogFiles.md @@ -0,0 +1,29 @@ +--- +layout: default +title: Clear Log Files +nav_order: 6 +parent: Diagnostics / Maintenance +grand_parent: Actions +WCVersion: 0.917 +--- +# Clear Log Files + +Release: >0.917 +{: .label .label-blue } + +### Description + +This function will delete the existing log.txt and alog.txt files. New ones will be created (rather instantaneously). + +### Process + +WebControl will attempt to delete each log file up to 1,000 times. The need for multiple attempts is that at any given point, WebControl might be writing to the log and if so, the file can't be deleted. So by attempting mulitple times, eventually the file will be closed and can get deleted. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Diagnostics-Maintenance/downloadDiagnostics.md b/docs/Actions/Diagnostics-Maintenance/downloadDiagnostics.md new file mode 100644 index 00000000..dc2e7c3d --- /dev/null +++ b/docs/Actions/Diagnostics-Maintenance/downloadDiagnostics.md @@ -0,0 +1,37 @@ +--- +layout: default +title: Download Diagnostics File +nav_order: 3 +parent: Diagnostics / Maintenance +grand_parent: Actions +WCVersion: 0.917 +--- +# Download Diagnostics File + +Release: >0.917 +{: .label .label-blue } + +### Description + +This function allows you to download a zip file containing diagnostic data from WebControl to assist in troubleshooting issues you may be experiencing. + +### Process + +Pressing the 'Download Diagnostics File' will instruct WebControl to create a zip file in the .WebControl directory containing the following: + +* webcontrol.json +* log.txt +* alog.txt + +The file will be named 'wc_diagnostics_XXXXX-YYYYY.zip' where XXXXXX is the date in YYMMDD format YYYYYY is the time in HHMMSS format. + +After creating the zip file, WebControl will send the file to the browser for the user to download. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + diff --git a/docs/Actions/Diagnostics-Maintenance/index.md b/docs/Actions/Diagnostics-Maintenance/index.md new file mode 100644 index 00000000..b6c31800 --- /dev/null +++ b/docs/Actions/Diagnostics-Maintenance/index.md @@ -0,0 +1,11 @@ +--- +layout: default +title: Diagnostics / Maintenance +nav_order: 3 +has_children: true +parent: Actions +--- +# Diagnostics/Maintenance + +Release: >0.906 +{: .label .label-blue } diff --git a/docs/Actions/Diagnostics-Maintenance/restoreWebControl.md b/docs/Actions/Diagnostics-Maintenance/restoreWebControl.md new file mode 100644 index 00000000..f18b0858 --- /dev/null +++ b/docs/Actions/Diagnostics-Maintenance/restoreWebControl.md @@ -0,0 +1,47 @@ +--- +layout: default +title: Restore WebControl +nav_order: 5 +parent: Diagnostics / Maintenance +grand_parent: Actions +WCVersion: 0.917 +--- +# Backup WebControl + +Release: >0.917 +{: .label .label-blue } + +### Description + +This function allows you to upload a webcontrol backup file to restore an installation of WebControl. The backup webcontrol file must have been made by the 'Backup WebControl' process. + +### Process + +Pressing the 'Restore WebControl' will request the user to upload a webcontrol backup file. WebControl will extract the contents of this file to the .WebControl directory. + +The extraction process overwrites existing files, but will not delete files that are present in the .WebControl directory but not present in the backup file. + +Files that will be restored include + +* Uploaded GCode files +* Board Management Files +* webcontrol.json +* log.txt +* alog.txt +* Imported files (like groundcontrol.ini) +* Downloaded upgrade files (see note below) + +After the files have been extracted, WebControl will reload the webcontrol.json file and synchronize those settings with the attached controller. + +**Note:** The backup files contain a copy of all the release versions to which you have upgraded. The release files are rather large (~70 MB) so the backup file will grow to be pretty large. A near-future release will delete the old files after an upgrade is complete. + +### Troubleshooting + +|Result |Possible Cause/Solution | +|--- |--- | +|xxxx |xxxx. | +|xxxx |xxxx. | + + + + diff --git a/docs/Actions/Diagnostics-Maintenance/testMotorsEncoders.md b/docs/Actions/Diagnostics-Maintenance/testMotorsEncoders.md new file mode 100644 index 00000000..224ffbb3 --- /dev/null +++ b/docs/Actions/Diagnostics-Maintenance/testMotorsEncoders.md @@ -0,0 +1,46 @@ +--- +layout: default +title: Test Motors/Encoders +nav_order: 1 +parent: Diagnostics / Maintenance +grand_parent: Actions +--- +# Test Motors/Encoders + +Release: >0.906 +{: .label .label-blue } + + +### Description +This function sends a test command to the controller to exercise the motors and read values from the encoders. + +### Process +Each axis is tested individually. For a stock machine (two motors and z-axis) the test sequence is: + +* Left Motor +* Right Motor +* Z-Axis + +For each motor, the following actions are taken (based upon current stock firmware as of 11/27/19): + +##### Forward Motion Test: +* Encoder position is read and stored. +* Motor is run "forward" at full power for one second +* Encoder position is read and stored. +* If the difference between the ending encoder position value and beginning encoder position value is **greater than** 500 steps, then indicate a PASS, otherwise indicate a FAIL. + +##### Reverse Motion Test: +* Encoder position is read and stored. +* Motor is run "reverse" at full power for one second +* Encoder position is read and stored. +* If the difference between the ending encoder position value and beginning encoder position value is **less than** than 500 steps, then indicate a PASS, otherwise indicate a FAIL. + +### Interpretation + +|Result |Possible Cause/Solution | +|--- |--- | +|All Motors Fail All Tests |Power cord is inserted into the Arduino controller instead of the motor controller shield. Check installation. | +|One or More Motors Fails Both Directions |Motor cable not inserted properly into either the motor controller shield or the motor. Unplug and replug the cable ends. | +|One or More Motors Fail One Direction |Possible hardware issue with motor or encoder | + + diff --git a/docs/Actions/index.md b/docs/Actions/index.md new file mode 100644 index 00000000..45dec8bd --- /dev/null +++ b/docs/Actions/index.md @@ -0,0 +1,10 @@ +--- +layout: default +title: Actions +nav_order: 3 +has_children: true +--- +# Actions + +Release: >0.906 +{: .label .label-blue } diff --git a/docs/Boards/boardManagement.md b/docs/Boards/boardManagement.md new file mode 100644 index 00000000..74001464 --- /dev/null +++ b/docs/Boards/boardManagement.md @@ -0,0 +1,56 @@ +--- +layout: default +title: Board Management +nav_order: 1 +parent: Boards +--- + +# Board Management + +Release: >0.906 +{: .label .label-blue } + +![Board](../assets/boards/boardCut.png) + +## Concept + +Board management as implemented in WebControl allows the user to track the areas of a given board that have been cut or otherwise marked by executing gcode. The system tracks cut areas at a 1-inch square resolution. That is, a standard 4-foot by 8-foot sheet of plywood is tracked by a 48 x 96 grid. + +## Functions + +### Create/Edit Board + +This function allows the user to define the size (width, height, thickness) of a board, provide identifying information (board ID, material type), and the position of center of the board on the frame. + +![Board Details](../assets/boards/createEditBoard.png) + +Board Details: +The "Board ID" can be any name or other identifier the user desires to give the board (e.g., Board 1, A1, MDF-1, etc.) The "Material" can be any description the user desires to enter (e.g, MDF, Plywood, Acrylic, Depleted Uranium, etc.) + +Board Dimensions: +The units of the board is based upon the unit setting for the machine. So if you have it set to metrics, your units will be reported in metric.. if in imperial, they will be reported in imperial. + +Board Positions: +Center X (horizontal) and Center Y (vertical) position of the center of the board with respect to the frame. A 4-foot x 8-foot sheet of plywood perfectly aligned on a 'standard' Maslow would have a Center X and Center Y of 0, 0. + +Align Board to Router allows the user to use the router's current position to indicate where the board is located. For boards that are not full sheet sizes, this makes it easy to align the board for cutting. For example, if the router is located at 12, 0 (1-foot to the right of center) and the board is perfectly centered under the router bit, pressing the 'Center' button will set the Center X and Center Y of the board to 12, 0. If, instead, the top right corner of a 1-foot board is located directly under the router bit, pressing 'Top Right' will set the Center X and Center Y of the board to 6, 0 (6-inches to the right of the center). + +### Process GCode + +![Board](../assets/boards/boardNotCutCut.png) + +The GCode that has been loaded will be used to mark areas on the board that have been cut. Obviously, this would be performed after you actually perform a cut. + +### Open / Save Board + +Allows user to save board data to the drive and open previously saved board data. + +### Trim GCode + +![Trim Board](../assets/boards/trimBoard.png) + +In the event the user cuts part of the board off (i.e., trims an edge), this function allows for the board data to be updated. For example, if the user cuts 1-foot off the top of the board, the user can enter 12 under 'Trim Top' and the top 12-inches will be removed from the board data. Note, this doesn't affect the value of Center X and Center Y. + +### Clear Board + +Clears all cut information from current board. diff --git a/docs/Boards/index.md b/docs/Boards/index.md new file mode 100644 index 00000000..3fe7c9c1 --- /dev/null +++ b/docs/Boards/index.md @@ -0,0 +1,10 @@ +--- +layout: default +title: Boards +nav_order: 4 +has_children: true +--- +# Boards Help Pages + +Release: >0.906 +{: .label .label-blue } diff --git a/docs/GettingStarted/__init__.py b/docs/GettingStarted/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/docs/GettingStarted/firstSteps.md b/docs/GettingStarted/firstSteps.md new file mode 100644 index 00000000..5da48618 --- /dev/null +++ b/docs/GettingStarted/firstSteps.md @@ -0,0 +1,79 @@ +--- +layout: default +title: First Steps +nav_order: 1 +parent: Getting Started +WCVersion: 0.915 +--- +# First Steps + +Release: >0.906 +{: .label .label-blue } + +## If you are coming from using GroundControl: + +If you are coming from using GroundControl, my recommendation is to import your groundcontrol.ini file before proceeding any further. + +Go to Actions->Import groundcontrol.ini + +If all goes well and the comport assignment is still the same, you should be able to communicate with the controller. + +## If you are starting anew: + +### 1) Set ComPort + +Go to Settings->Maslow Settings->COMPort and select the comport for the arduino controller. Press the 'refresh' symbol to populate the list of available comports (give it a couple of seconds if you have a bluetooth enabled on the computer running webcontrol). Don't forget to press submit. If all goes well, you should see messages coming from the controller in the lower right portion of the screen (Controller Messages) + +![COMPort Setting](../assets/gettingStarted/comPort.png) + +_COMPort Setting_ + +### 2) Set Distance to Extend Chains + +If you are using a top beam that's longer than 10 feet, go to Settings->Advanced Settings->Extend Chain Distance. If using a 12-foot beam, change to 2032. This is the amount of chain that will be extended to allow you to connect up the sled. Too little and they won't meet and too much, the sled may be on the floor. You don't have to use a value that perfectly equates to the center of the board, just make sure it's a multiple of 6.35 mm. + +![Extemd Chain Distance](../assets/gettingStarted/extendChainDistance.png) + +_Extend Chain Distance_ + +### 3) Quick Configure + +Go to Actions->Quick Configure and enter the requested information. This lets the controller know enough about the setup to allow you to calibrate the machine. Don't forget to press submit. + +### 4) Set Sprockets Vertical + +Go to Actions->Set Sprockets & Reset Chains: + +4a) Get one tooth of each sprocket as precisely vertical as you can using the buttons. When done, press 'Define Zero'. This tells the controllers that the chain length is 0. + +![Sprocket with Vertical Tooth](../assets/gettingStarted/Sprocket%20at%2012-00.png) + +_Sprocket with Vertical Tooth_ + +4b) Install the chains on the sprocket such that the first link is resting on the top sprocket tooth. The placement depends on if you built the frame for "Chains Off Top" or "Chains Off Bottom" + +![Chains Off Bottom](../assets/gettingStarted/chainOffSprocketsBottom.png) + +_Chains Off Bottom_ + +![Chains Off Top](../assets/gettingStarted/chainOffSprocketsTop.png) + +_Chains Off Top_ + +4c) Extend left chain. Press 'Extend Left Chain to xxxx mm' where xxxx is the distance set in Step 2. Warning: This is one spot where the chains can get wrapped around the sprocket. Grab hold of the end of the chain and apply tension to it as it feeds off the sprocket so it doesn't wrap. + +4d) Extend right chain. Press 'Extend Right Chain to xxxx mm' where xxxx is the distance set in Step 2. Warning: Same as above. + +4e) Connect Sled. Connect up your sled to the extended chains. + +4f) Mark chains. Take a marker, nail polish, something, and mark the specific chain link that is on top of the top tooth. If the 'Extend Chain Distance' is a multiple of 6.35 mm, there should be a tooth perfectly vertical after extending the chains. Mark this because if you ever have to reset the chains, you need to know which link is this one. + +### 5) Calibrate + +If using stock firwmare, go to: + + [Triangular Calibration]({{ site.baseurl }}{% link Actions/Calibration-Setup/triangularCalibration.md %}) + +If using holey calibration firmware, go to: + + [Holey Calibration]({{ site.baseurl }}{% link Actions/Calibration-Setup/holeyCalibration.md %}) diff --git a/docs/GettingStarted/index.md b/docs/GettingStarted/index.md new file mode 100644 index 00000000..57f13bce --- /dev/null +++ b/docs/GettingStarted/index.md @@ -0,0 +1,10 @@ +--- +layout: default +title: Getting Started +nav_order: 2 +has_children: true +--- +# Getting Started + +Release: >0.906 +{: .label .label-blue } diff --git a/docs/_config.yml b/docs/_config.yml new file mode 100644 index 00000000..457d7a54 --- /dev/null +++ b/docs/_config.yml @@ -0,0 +1 @@ +remote_theme: pmarsceill/just-the-docs diff --git a/docs/assets/Actions/Calibration-Setup/index.md b/docs/assets/Actions/Calibration-Setup/index.md new file mode 100644 index 00000000..3d7d7777 --- /dev/null +++ b/docs/assets/Actions/Calibration-Setup/index.md @@ -0,0 +1,34 @@ +--- +layout: default +title: Calibration / Setup +nav_exclude: true +--- + +# Calibration / Setup + +Release: >0.906 +{: .label .label-blue } + +###### TABLE OF CONTENTS + +[Import groundcontrol.ini File](Actions/Calibration-Setup/importGroundControlini.md) + +[Import webcontrol.json File](Actions/Calibration-Setup/importWebcontroljson.md) + +[Quick Configure](Actions/Calibration-Setup/quickConfigure.md) + +[Set Sprockets & Reset Chains](Actions/Calibration-Setup/setSprocketsVertical.md) + +[Triangular Calibration](Actions/Calibration-Setup/triangularCalibration.md) + +[Holey Calibration](Actions/Calibration-Setup/holeyCalibration.md) + +[Return to Center](Actions/Calibration-Setup/returnToCenter.md) + +[Check for Chain Skip](Actions/Calibration-Setup/checkForChainSkip.md) + + + + + + diff --git a/docs/assets/Actions/Calibration-Setup/markedLinkAtTop.png b/docs/assets/Actions/Calibration-Setup/markedLinkAtTop.png new file mode 100644 index 00000000..99c7339a Binary files /dev/null and b/docs/assets/Actions/Calibration-Setup/markedLinkAtTop.png differ diff --git a/docs/assets/Actions/Calibration-Setup/setSprocketsVertical.png b/docs/assets/Actions/Calibration-Setup/setSprocketsVertical.png new file mode 100644 index 00000000..cda1b4a0 Binary files /dev/null and b/docs/assets/Actions/Calibration-Setup/setSprocketsVertical.png differ diff --git a/docs/assets/Actions/Controller/index.md b/docs/assets/Actions/Controller/index.md new file mode 100644 index 00000000..c245f358 --- /dev/null +++ b/docs/assets/Actions/Controller/index.md @@ -0,0 +1,31 @@ +--- +layout: default +title: Controller +nav_exclude: true +--- + +# Controller + +Release: >0.906 +{: .label .label-blue } + +###### TABLE OF CONTENTS + +[Upgrade Stock Firmware](Actions/Controller/upgradeStockFirmware.md) + +[Upgrade Holey Firmware](Actions/Controller/upgradeHoleyFirmware.md) + +[Upgrade Custom Firmware](Actions/Controller/upgradeCustomFirmware.md) + +[Sync Settings](Actions/Controller/syncSettings.md) + +[Wipe Controller Settings](Actions/Controller/wipeControllerSettings.md) + +[Wipe Controller Position & Settings](Actions/Controller/wipeControllerPositionAndSettings.md) + +[Wipe Controller EEPROM](Actions/Controller/wipeControllerEEPROM.md) + + + + + diff --git a/docs/assets/Actions/Diagnostics-Maintenance/index.md b/docs/assets/Actions/Diagnostics-Maintenance/index.md new file mode 100644 index 00000000..47660c30 --- /dev/null +++ b/docs/assets/Actions/Diagnostics-Maintenance/index.md @@ -0,0 +1,25 @@ +--- +layout: default +title: Diagnostics / Maintenance +nav_exclude: true +--- + +# Diagnostics / Maintenance + +Release: >0.906 +{: .label .label-blue } + +###### TABLE OF CONTENTS + +[Test Motors/Encoders](Actions/Diagnostics-Maintenance/testMotorsEncoders.md) + +[Download Diagnostics File](Actions/Diagnostics-Maintenance/downloadDiagnostics.md) + +[Backup WebControl](Actions/Diagnostics-Maintenance/backupWebControl.md) + +[Restore WebControl](Actions/Diagnostics-Maintenance/restoreWebControl.md) + +[Clear Log Files](Actions/Diagnostics-Maintenance/clearLogFiles.md) + + + diff --git a/docs/assets/Actions/index.md b/docs/assets/Actions/index.md new file mode 100644 index 00000000..3b1044cc --- /dev/null +++ b/docs/assets/Actions/index.md @@ -0,0 +1,25 @@ +--- +layout: default +title: Actions +nav_exclude: true +--- + +# Actions + +Release: >0.906 +{: .label .label-blue } + +###### TABLE OF CONTENTS + +[Diagnostics / Maintenance](assets/Actions/Diagnostics-Maintenance/index.md) + +[Calibration / Setup](assets/Actions/Calibration-Setup/index.md) + +[Controller](assets/Actions/Controller/index.md) + + + + + + + diff --git a/docs/assets/Screenshot.png b/docs/assets/Screenshot.png new file mode 100644 index 00000000..00362eaa Binary files /dev/null and b/docs/assets/Screenshot.png differ diff --git a/docs/assets/boards/boardCut.png b/docs/assets/boards/boardCut.png new file mode 100644 index 00000000..6d68b6c6 Binary files /dev/null and b/docs/assets/boards/boardCut.png differ diff --git a/docs/assets/boards/boardNotCut.png b/docs/assets/boards/boardNotCut.png new file mode 100644 index 00000000..f5c6dbb8 Binary files /dev/null and b/docs/assets/boards/boardNotCut.png differ diff --git a/docs/assets/boards/boardNotCutCut.png b/docs/assets/boards/boardNotCutCut.png new file mode 100644 index 00000000..4bfa874f Binary files /dev/null and b/docs/assets/boards/boardNotCutCut.png differ diff --git a/docs/assets/boards/createEditBoard.png b/docs/assets/boards/createEditBoard.png new file mode 100644 index 00000000..2884ae29 Binary files /dev/null and b/docs/assets/boards/createEditBoard.png differ diff --git a/docs/assets/boards/trimBoard.png b/docs/assets/boards/trimBoard.png new file mode 100644 index 00000000..66f26456 Binary files /dev/null and b/docs/assets/boards/trimBoard.png differ diff --git a/docs/assets/gettingStarted/Sprocket at 12-00.png b/docs/assets/gettingStarted/Sprocket at 12-00.png new file mode 100644 index 00000000..4bde7e94 Binary files /dev/null and b/docs/assets/gettingStarted/Sprocket at 12-00.png differ diff --git a/docs/assets/gettingStarted/chainOffSprocketsBottom.png b/docs/assets/gettingStarted/chainOffSprocketsBottom.png new file mode 100644 index 00000000..66dca318 Binary files /dev/null and b/docs/assets/gettingStarted/chainOffSprocketsBottom.png differ diff --git a/docs/assets/gettingStarted/chainOffSprocketsTop.png b/docs/assets/gettingStarted/chainOffSprocketsTop.png new file mode 100644 index 00000000..33cadccd Binary files /dev/null and b/docs/assets/gettingStarted/chainOffSprocketsTop.png differ diff --git a/docs/assets/gettingStarted/comPort.png b/docs/assets/gettingStarted/comPort.png new file mode 100644 index 00000000..dcd38a6e Binary files /dev/null and b/docs/assets/gettingStarted/comPort.png differ diff --git a/docs/assets/gettingStarted/extendChainDistance.png b/docs/assets/gettingStarted/extendChainDistance.png new file mode 100644 index 00000000..1d50a8cf Binary files /dev/null and b/docs/assets/gettingStarted/extendChainDistance.png differ diff --git a/docs/assets/helpPages.md b/docs/assets/helpPages.md new file mode 100644 index 00000000..ae856643 --- /dev/null +++ b/docs/assets/helpPages.md @@ -0,0 +1,29 @@ +--- +layout: default +title: Help Pages +nav_exclude: true +--- + +#### Index + +###### Home + +[Home](help) + +###### Getting Started + +[First Steps](GettingStarted/firstSteps.md) + +###### [Actions](assets/Actions/index.md) + +[Diagnostics/Maintenance](assets/Actions/Diagnostics-Maintenance/index.md) + +[Calibration/Setup](assets/Actions/Calibration-Setup/index.md) + +[Controller](assets/Actions/Controller/index.md) + +###### Boards + +[Board Management](Boards/boardManagement.md) + + diff --git a/docs/assets/holeyCalibration/acceptResults.png b/docs/assets/holeyCalibration/acceptResults.png new file mode 100644 index 00000000..2f43dc7a Binary files /dev/null and b/docs/assets/holeyCalibration/acceptResults.png differ diff --git a/docs/assets/holeyCalibration/calculate.png b/docs/assets/holeyCalibration/calculate.png new file mode 100644 index 00000000..21cb600b Binary files /dev/null and b/docs/assets/holeyCalibration/calculate.png differ diff --git a/docs/assets/holeyCalibration/cutPattern.png b/docs/assets/holeyCalibration/cutPattern.png new file mode 100644 index 00000000..503fd72f Binary files /dev/null and b/docs/assets/holeyCalibration/cutPattern.png differ diff --git a/docs/assets/holeyCalibration/measurements.png b/docs/assets/holeyCalibration/measurements.png new file mode 100644 index 00000000..02487f47 Binary files /dev/null and b/docs/assets/holeyCalibration/measurements.png differ diff --git a/docs/assets/triangularCalibration/acceptResults.png b/docs/assets/triangularCalibration/acceptResults.png new file mode 100644 index 00000000..bff67888 Binary files /dev/null and b/docs/assets/triangularCalibration/acceptResults.png differ diff --git a/docs/assets/triangularCalibration/calculate.png b/docs/assets/triangularCalibration/calculate.png new file mode 100644 index 00000000..1d088cee Binary files /dev/null and b/docs/assets/triangularCalibration/calculate.png differ diff --git a/docs/assets/triangularCalibration/cutPattern.png b/docs/assets/triangularCalibration/cutPattern.png new file mode 100644 index 00000000..cce0ae9c Binary files /dev/null and b/docs/assets/triangularCalibration/cutPattern.png differ diff --git a/docs/assets/triangularCalibration/enterMeasurements.png b/docs/assets/triangularCalibration/enterMeasurements.png new file mode 100644 index 00000000..7608442e Binary files /dev/null and b/docs/assets/triangularCalibration/enterMeasurements.png differ diff --git a/docs/assets/triangularCalibration/measurements.png b/docs/assets/triangularCalibration/measurements.png new file mode 100644 index 00000000..6a6a9bfb Binary files /dev/null and b/docs/assets/triangularCalibration/measurements.png differ diff --git a/docs/index.md b/docs/index.md new file mode 100644 index 00000000..66651377 --- /dev/null +++ b/docs/index.md @@ -0,0 +1,112 @@ +--- +layout: default +title: Home +nav_order: 1 +description: Help pages for WebControl +wcversion: 0.915.001 +--- + +# WebControl + +On Github: [madgrizzle/WebControl](https://github.com/madgrizzle/WebControl) + +Report Issues: [madgrizzle/WebControl/issues](https://github.com/madgrizzle/WebControl/issues) + +WebControl is a browser-based implementation of [MaslowCNC/GroundControl](https://github.com/MaslowCNC/GroundControl) for controlling a Maslow CNC. Ground Control utilizes Kivy as the graphic front end, which makes it difficult to implement multiple and/or remote access. WebControl, however, runs completely as a flask-socketio web server and inherently supports remote access and multiple screens. Therefore, WebControl can be installed on a low cost device like a Raspberry Pi, Windows 10, or linux (Debian) machines and the user can utilize their laptop, tablet and/or phone to control it.. all at the same time. Since the the installation supports headless operation, someone trying to build a self contained sled (i.e., motors located on the sled) can also install the Raspberry Pi on the sled as well. + +Screenshot +## Notice + +Webcontrol will be moving all releases to a pyinstaller created executable, including for the Raspberry Pi. I will try to create a pre-built image for the RPI, but until then you will need to install a copy of raspbian on an SD card, update it for SSH and network access, then download webcontrol and set it to run automatically (if you chose). + +### Windows 10 and Linux Single-File Releases + +For Windows 10 and Linux (Debian-based, such as Ubuntu) machines, users can download the latest single-file release, extract it, and run webcontrol. As a single-file release, it is completely portable and does not require an installation. The file unpacks itself into a temporary directory and runs. If you have a very slow computer, it might take a while to unpack. In that case, it is recommended to use the single-directory release which extracts into a single directory containing unpacked files. Startup is much quicker using single-directory releases versus a single-file release. + +Check out the release page at: + +[https://github.com/madgrizzle/WebControl/releases](https://github.com/madgrizzle/WebControl/releases) + +### Raspberry Pi (3B+ & Zero W) + +For Raspberry Pi's, single-directory releases are your best option. It can take up to a minute to unpack a single-file release on a Raspberry Pi 3B+. Single-directory releases unpack the files into the directory so startup is much quicker. Both the Raspberry Pi 3B+ and Zero W have been tested to work with webcontrol. Other versions likely would also. I recommend the 3B+ if you are trying to decide. + +Check out the release page at: + +[https://github.com/madgrizzle/WebControl/releases](https://github.com/madgrizzle/WebControl/releases) + +## Built With + +* [Flask](http://flask.pocoo.org/) - The web framework used +* [Flask-Socketio](https://github.com/miguelgrinberg/Flask-SocketIO) - Websocket integration for communications with browser clients +* [Bootstrap4](https://getbootstrap.com/) - Front-end component library +* [Jinja2](http://jinja.pocoo.org/) - Template engine for web page generation +* [Feather.js](https://feathericons.com/) - Only icon library I could find that had diagonal arrows.. works well to boot. +* [OpenCV](https://github.com/skvark/opencv-python) - Library for computer vision to implement optical calibration +* [Numpy](http://www.numpy.org) - Library for math routines used with optical calibration +* [Scipy](http://www.scipy.org) - Another library for math routines used with optical calibration +* [Imutils](https://github.com/jrosebr1/imutils) - Adrian Rosebrock's library used with optical calibration +* [Schedule](https://github.com/dbader/schedule) - Library used to schedule checking connection with arduino +* [Ground Control](https://github.com/maslowcnc/groundcontrol) - Much of this was adapted from the Kivy-based Ground Control + + +## Developing + +### Virtualenv + +You can use virtualenv to set up a local development environment for running the code without installing packages in the system Python installation. + + # Create a virtual environment + virtualenv -p python3 .venv + # Activate the virtual environment + source .venv/bin/activate + # Install the prerequisites + pip install -r requirements.txt + +When running on the Pi, you'll also need some extra dependencies and will need to build OpenCV from source. See the Dockerfile for details. (TODO: add instructions here) + +Then you can run the code with. + + python main.py + +The server will then be available at http://localhost:5000 + +### Automatic code formatting + +This project uses [black](https://github.com/ambv/black) to automatically format python code. To run the autoformatter, simply install black locally with `pip`. + + pip install black + +Subsequently, you can just run `black .` to format all files in the current directory. + + black . + +If you don't have python3.6+ locally (to be able to run `black`), you can run `black` in a Docker container. + + docker run -v $(pwd):/code johnboiles/python-black . + +### IDE + +[Pycharm Community Edition](https://www.jetbrains.com/pycharm/download) is a free, well-featured Python IDE. + +With the [File Watchers](https://plugins.jetbrains.com/plugin/7177-file-watchers) and [BlackPycharm](https://plugins.jetbrains.com/plugin/10563-black-pycharm) plugins you can set up your editor to automatically format your code on save. Then you never have to think about code formatting again :tada: + +## Contributing + +Please read [CONTRIBUTING.md](https://gist.github.com/PurpleBooth/b24679402957c63ec426) for details on our code of conduct, and the process for submitting pull requests to us. + +## Versioning + +Added to TODO list? + +## Authors + +* **Madgrizzle** - *Initial work* - [madgrizzle](https://github.com/madgrizzle) +* **John Boiles** - *Docker Expert* - [johnboiles](https://github.com/johnboiles) +* **Tinker** - *UI Improvements/Bug Fixer/Etc.* - [gb0101010101](https://github.com/gb0101010101) + +See also the list of [contributors](https://github.com/your/project/contributors) who participated in this project. + +## License + +See [LICENSE](https://github.com/madgrizzle/WebControl/blob/master/LICENSE) diff --git a/gcode/flag4-a.nc b/gcode/flag4-a.nc deleted file mode 100644 index 3468aba9..00000000 --- a/gcode/flag4-a.nc +++ /dev/null @@ -1,4695 +0,0 @@ -(Generated by PartKam Version 0.05) - -G20 G90 G40 - -(pocket 1) -G0 Z0.25 -T1 M6 -G17 -M3 -G0 X6.7974 Y9.4285 -G1 Z-0.05 F30 -G1 X6.7383 Y9.6197 F10 -G3 X6.6191 Y9.6205 I-0.0597 J-0.0185 -G1 X6.5567 Y9.4285 -G1 X6.3548 Y9.4285 -G3 X6.2923 Y9.366 I0 J-0.0625 -G3 X6.3181 Y9.3154 I0.0625 J0 -G1 X6.4814 Y9.1967 -G1 X6.419 Y9.0046 -G3 X6.4159 Y8.9853 I0.0594 J-0.0193 -G3 X6.5151 Y8.9347 I0.0625 J0 -G1 X6.6786 Y9.0534 -G1 X6.8421 Y8.9347 -G3 X6.9413 Y8.9853 I0.0367 J0.0506 -G3 X6.9383 Y9.0046 I-0.0625 J0 -G1 X6.8758 Y9.1967 -G1 X7.0392 Y9.3154 -G3 X7.0649 Y9.366 I-0.0367 J0.0506 -G3 X7.0024 Y9.4285 I-0.0625 J0 -G1 X6.7974 Y9.4285 -G0 Z0.25 -G0 X6.7974 Y7.2722 -G1 Z-0.05 F30 -G1 X6.7383 Y7.4635 F10 -G3 X6.6191 Y7.4643 I-0.0597 J-0.0185 -G1 X6.5567 Y7.2722 -G1 X6.3548 Y7.2722 -G3 X6.2923 Y7.2097 I0 J-0.0625 -G3 X6.3181 Y7.1591 I0.0625 J0 -G1 X6.4814 Y7.0404 -G1 X6.419 Y6.8484 -G3 X6.4159 Y6.829 I0.0594 J-0.0193 -G3 X6.5151 Y6.7785 I0.0625 J0 -G1 X6.6786 Y6.8972 -G1 X6.8421 Y6.7784 -G3 X6.9413 Y6.829 I0.0367 J0.0506 -G3 X6.9383 Y6.8484 I-0.0625 J0 -G1 X6.8758 Y7.0404 -G1 X7.0392 Y7.1591 -G3 X7.0649 Y7.2097 I-0.0367 J0.0506 -G3 X7.0024 Y7.2722 I-0.0625 J0 -G1 X6.7974 Y7.2722 -G0 Z0.25 -G0 X6.7974 Y6.194 -G1 Z-0.05 F30 -G1 X6.7383 Y6.3853 F10 -G3 X6.6191 Y6.3861 I-0.0597 J-0.0185 -G1 X6.5567 Y6.194 -G1 X6.3548 Y6.194 -G3 X6.2923 Y6.1315 I0 J-0.0625 -G3 X6.3181 Y6.081 I0.0625 J0 -G1 X6.4814 Y5.9622 -G1 X6.419 Y5.7702 -G3 X6.4159 Y5.7508 I0.0594 J-0.0193 -G3 X6.5151 Y5.7003 I0.0625 J0 -G1 X6.6786 Y5.819 -G1 X6.8421 Y5.7002 -G3 X6.9413 Y5.7508 I0.0367 J0.0506 -G3 X6.9383 Y5.7702 I-0.0625 J0 -G1 X6.8758 Y5.9622 -G1 X7.0392 Y6.081 -G3 X7.0649 Y6.1315 I-0.0367 J0.0506 -G3 X7.0024 Y6.194 I-0.0625 J0 -G1 X6.7974 Y6.194 -G0 Z0.25 -G0 X5.5319 Y8.3503 -G1 Z-0.05 F30 -G1 X5.4727 Y8.5415 F10 -G3 X5.3535 Y8.5423 I-0.0597 J-0.0185 -G1 X5.2912 Y8.3503 -G1 X5.0891 Y8.3503 -G3 X5.0266 Y8.2878 I0 J-0.0625 -G3 X5.0524 Y8.2372 I0.0625 J0 -G1 X5.2158 Y8.1185 -G1 X5.1534 Y7.9264 -G3 X5.1503 Y7.9071 I0.0594 J-0.0193 -G3 X5.2496 Y7.8565 I0.0625 J0 -G1 X5.413 Y7.9752 -G1 X5.5764 Y7.8565 -G3 X5.6756 Y7.9071 I0.0367 J0.0506 -G3 X5.6726 Y7.9264 I-0.0625 J0 -G1 X5.6102 Y8.1185 -G1 X5.7736 Y8.2372 -G3 X5.7994 Y8.2878 I-0.0367 J0.0506 -G3 X5.7369 Y8.3503 I-0.0625 J0 -G1 X5.5319 Y8.3503 -G0 Z0.25 -G0 X3.6334 Y8.8893 -G1 Z-0.05 F30 -G1 X3.5742 Y9.0805 F10 -G3 X3.4551 Y9.0814 I-0.0597 J-0.0185 -G1 X3.3927 Y8.8893 -G1 X3.1908 Y8.8893 -G3 X3.1283 Y8.8268 I0 J-0.0625 -G3 X3.154 Y8.7762 I0.0625 J0 -G1 X3.3174 Y8.6575 -G1 X3.2549 Y8.4654 -G3 X3.2519 Y8.4461 I0.0594 J-0.0193 -G3 X3.3511 Y8.3955 I0.0625 J0 -G1 X3.5145 Y8.5143 -G1 X3.6779 Y8.3955 -G3 X3.7772 Y8.4461 I0.0367 J0.0506 -G3 X3.7741 Y8.4654 I-0.0625 J0 -G1 X3.7117 Y8.6575 -G1 X3.8751 Y8.7762 -G3 X3.9009 Y8.8268 I-0.0367 J0.0506 -G3 X3.8384 Y8.8893 I-0.0625 J0 -G1 X3.6334 Y8.8893 -G0 Z0.25 -G0 X6.1646 Y6.733 -G1 Z-0.05 F30 -G1 X6.1055 Y6.9243 F10 -G3 X5.9863 Y6.9251 I-0.0597 J-0.0185 -G1 X5.924 Y6.733 -G1 X5.722 Y6.733 -G3 X5.6595 Y6.6705 I0 J-0.0625 -G3 X5.6853 Y6.62 I0.0625 J0 -G1 X5.8487 Y6.5013 -G1 X5.7862 Y6.3092 -G3 X5.7831 Y6.2899 I0.0594 J-0.0193 -G3 X5.8824 Y6.2393 I0.0625 J0 -G1 X6.0458 Y6.358 -G1 X6.2092 Y6.2393 -G3 X6.3084 Y6.2899 I0.0367 J0.0506 -G3 X6.3053 Y6.3092 I-0.0625 J0 -G1 X6.243 Y6.5013 -G1 X6.4064 Y6.62 -G3 X6.4322 Y6.6705 I-0.0367 J0.0506 -G3 X6.3697 Y6.733 I-0.0625 J0 -G1 X6.1646 Y6.733 -G0 Z0.25 -G0 X4.2662 Y8.3503 -G1 Z-0.05 F30 -G1 X4.207 Y8.5415 F10 -G3 X4.0878 Y8.5423 I-0.0597 J-0.0185 -G1 X4.0255 Y8.3503 -G1 X3.8235 Y8.3503 -G3 X3.761 Y8.2878 I0 J-0.0625 -G3 X3.7868 Y8.2372 I0.0625 J0 -G1 X3.9502 Y8.1185 -G1 X3.8877 Y7.9264 -G3 X3.8847 Y7.9071 I0.0594 J-0.0193 -G3 X3.9839 Y7.8565 I0.0625 J0 -G1 X4.1473 Y7.9752 -G1 X4.3108 Y7.8565 -G3 X4.4101 Y7.9071 I0.0367 J0.0506 -G3 X4.407 Y7.9264 I-0.0625 J0 -G1 X4.3445 Y8.1185 -G1 X4.5079 Y8.2372 -G3 X4.5337 Y8.2878 I-0.0367 J0.0506 -G3 X4.4712 Y8.3503 I-0.0625 J0 -G1 X4.2662 Y8.3503 -G0 Z0.25 -G0 X4.2662 Y9.4285 -G1 Z-0.05 F30 -G1 X4.207 Y9.6197 F10 -G3 X4.0878 Y9.6205 I-0.0597 J-0.0185 -G1 X4.0255 Y9.4285 -G1 X3.8235 Y9.4285 -G3 X3.761 Y9.366 I0 J-0.0625 -G3 X3.7868 Y9.3154 I0.0625 J0 -G1 X3.9502 Y9.1967 -G1 X3.8877 Y9.0046 -G3 X3.8847 Y8.9853 I0.0594 J-0.0193 -G3 X3.9839 Y8.9347 I0.0625 J0 -G1 X4.1473 Y9.0534 -G1 X4.3108 Y8.9347 -G3 X4.4101 Y8.9853 I0.0367 J0.0506 -G3 X4.407 Y9.0046 I-0.0625 J0 -G1 X4.3445 Y9.1967 -G1 X4.5079 Y9.3154 -G3 X4.5337 Y9.366 I-0.0367 J0.0506 -G3 X4.4712 Y9.4285 I-0.0625 J0 -G1 X4.2662 Y9.4285 -G0 Z0.25 -G0 X3.6334 Y6.733 -G1 Z-0.05 F30 -G1 X3.5742 Y6.9243 F10 -G3 X3.4551 Y6.9251 I-0.0597 J-0.0185 -G1 X3.3927 Y6.733 -G1 X3.1908 Y6.733 -G3 X3.1283 Y6.6705 I0 J-0.0625 -G3 X3.154 Y6.62 I0.0625 J0 -G1 X3.3174 Y6.5013 -G1 X3.2549 Y6.3092 -G3 X3.2519 Y6.2899 I0.0594 J-0.0193 -G3 X3.3511 Y6.2393 I0.0625 J0 -G1 X3.5145 Y6.358 -G1 X3.6779 Y6.2393 -G3 X3.7772 Y6.2899 I0.0367 J0.0506 -G3 X3.7741 Y6.3092 I-0.0625 J0 -G1 X3.7117 Y6.5013 -G1 X3.8751 Y6.62 -G3 X3.9009 Y6.6705 I-0.0367 J0.0506 -G3 X3.8384 Y6.733 I-0.0625 J0 -G1 X3.6334 Y6.733 -G0 Z0.25 -G0 X3.0006 Y7.2722 -G1 Z-0.05 F30 -G1 X2.9414 Y7.4635 F10 -G3 X2.8223 Y7.4643 I-0.0597 J-0.0185 -G1 X2.7599 Y7.2722 -G1 X2.5578 Y7.2722 -G3 X2.4953 Y7.2097 I0 J-0.0625 -G3 X2.5211 Y7.1591 I0.0625 J0 -G1 X2.6845 Y7.0404 -G1 X2.6222 Y6.8483 -G3 X2.6191 Y6.829 I0.0594 J-0.0193 -G3 X2.7183 Y6.7785 I0.0625 J0 -G1 X2.8817 Y6.8972 -G1 X3.0451 Y6.7785 -G3 X3.1444 Y6.829 I0.0367 J0.0506 -G3 X3.1413 Y6.8483 I-0.0625 J0 -G1 X3.079 Y7.0404 -G1 X3.2424 Y7.1591 -G3 X3.2681 Y7.2097 I-0.0367 J0.0506 -G3 X3.2056 Y7.2722 I-0.0625 J0 -G1 X3.0006 Y7.2722 -G0 Z0.25 -G0 X5.5319 Y6.194 -G1 Z-0.05 F30 -G1 X5.4727 Y6.3853 F10 -G3 X5.3535 Y6.3861 I-0.0597 J-0.0185 -G1 X5.2912 Y6.194 -G1 X5.0891 Y6.194 -G3 X5.0266 Y6.1315 I0 J-0.0625 -G3 X5.0524 Y6.081 I0.0625 J0 -G1 X5.2158 Y5.9622 -G1 X5.1534 Y5.7701 -G3 X5.1503 Y5.7508 I0.0594 J-0.0193 -G3 X5.2496 Y5.7003 I0.0625 J0 -G1 X5.413 Y5.819 -G1 X5.5764 Y5.7003 -G3 X5.6756 Y5.7508 I0.0367 J0.0506 -G3 X5.6726 Y5.7701 I-0.0625 J0 -G1 X5.6102 Y5.9622 -G1 X5.7736 Y6.081 -G3 X5.7994 Y6.1315 I-0.0367 J0.0506 -G3 X5.7369 Y6.194 I-0.0625 J0 -G1 X5.5319 Y6.194 -G0 Z0.25 -G0 X1.1021 Y6.733 -G1 Z-0.05 F30 -G1 X1.043 Y6.9243 F10 -G3 X0.9238 Y6.9251 I-0.0597 J-0.0185 -G1 X0.8615 Y6.733 -G1 X0.6595 Y6.733 -G3 X0.597 Y6.6705 I0 J-0.0625 -G3 X0.6228 Y6.62 I0.0625 J0 -G1 X0.7862 Y6.5013 -G1 X0.7237 Y6.3092 -G3 X0.7206 Y6.2899 I0.0594 J-0.0193 -G3 X0.8199 Y6.2393 I0.0625 J0 -G1 X0.9833 Y6.358 -G1 X1.1467 Y6.2393 -G3 X1.2459 Y6.2899 I0.0367 J0.0506 -G3 X1.2428 Y6.3092 I-0.0625 J0 -G1 X1.1805 Y6.5013 -G1 X1.3439 Y6.62 -G3 X1.3697 Y6.6705 I-0.0367 J0.0506 -G3 X1.3072 Y6.733 I-0.0625 J0 -G1 X1.1021 Y6.733 -G0 Z0.25 -G0 X3.0006 Y8.3503 -G1 Z-0.05 F30 -G1 X2.9414 Y8.5415 F10 -G3 X2.8223 Y8.5423 I-0.0597 J-0.0185 -G1 X2.7599 Y8.3503 -G1 X2.5578 Y8.3503 -G3 X2.4953 Y8.2878 I0 J-0.0625 -G3 X2.5211 Y8.2372 I0.0625 J0 -G1 X2.6845 Y8.1185 -G1 X2.6222 Y7.9264 -G3 X2.6191 Y7.9071 I0.0594 J-0.0193 -G3 X2.7183 Y7.8565 I0.0625 J0 -G1 X2.8817 Y7.9752 -G1 X3.0451 Y7.8565 -G3 X3.1444 Y7.9071 I0.0367 J0.0506 -G3 X3.1413 Y7.9264 I-0.0625 J0 -G1 X3.079 Y8.1185 -G1 X3.2424 Y8.2372 -G3 X3.2681 Y8.2878 I-0.0367 J0.0506 -G3 X3.2056 Y8.3503 I-0.0625 J0 -G1 X3.0006 Y8.3503 -G0 Z0.25 -G0 X1.7349 Y7.2722 -G1 Z-0.05 F30 -G1 X1.6758 Y7.4635 F10 -G3 X1.5566 Y7.4643 I-0.0597 J-0.0185 -G1 X1.4942 Y7.2722 -G1 X1.2923 Y7.2722 -G3 X1.2298 Y7.2097 I0 J-0.0625 -G3 X1.2556 Y7.1591 I0.0625 J0 -G1 X1.4189 Y7.0404 -G1 X1.3565 Y6.8484 -G3 X1.3534 Y6.829 I0.0594 J-0.0193 -G3 X1.4526 Y6.7785 I0.0625 J0 -G1 X1.6161 Y6.8972 -G1 X1.7796 Y6.7784 -G3 X1.8788 Y6.829 I0.0367 J0.0506 -G3 X1.8758 Y6.8484 I-0.0625 J0 -G1 X1.8133 Y7.0404 -G1 X1.9767 Y7.1591 -G3 X2.0024 Y7.2097 I-0.0367 J0.0506 -G3 X1.9399 Y7.2722 I-0.0625 J0 -G1 X1.7349 Y7.2722 -G0 Z0.25 -G0 X4.2662 Y7.2722 -G1 Z-0.05 F30 -G1 X4.207 Y7.4635 F10 -G3 X4.0878 Y7.4643 I-0.0597 J-0.0185 -G1 X4.0255 Y7.2722 -G1 X3.8235 Y7.2722 -G3 X3.761 Y7.2097 I0 J-0.0625 -G3 X3.7868 Y7.1591 I0.0625 J0 -G1 X3.9502 Y7.0404 -G1 X3.8877 Y6.8484 -G3 X3.8847 Y6.829 I0.0594 J-0.0193 -G3 X3.9839 Y6.7785 I0.0625 J0 -G1 X4.1473 Y6.8972 -G1 X4.3108 Y6.7784 -G3 X4.4101 Y6.829 I0.0367 J0.0506 -G3 X4.407 Y6.8484 I-0.0625 J0 -G1 X4.3445 Y7.0404 -G1 X4.5079 Y7.1591 -G3 X4.5337 Y7.2097 I-0.0367 J0.0506 -G3 X4.4712 Y7.2722 I-0.0625 J0 -G1 X4.2662 Y7.2722 -G0 Z0.25 -G0 X1.1021 Y8.8893 -G1 Z-0.05 F30 -G1 X1.043 Y9.0805 F10 -G3 X0.9238 Y9.0814 I-0.0597 J-0.0185 -G1 X0.8615 Y8.8893 -G1 X0.6595 Y8.8893 -G3 X0.597 Y8.8268 I0 J-0.0625 -G3 X0.6228 Y8.7762 I0.0625 J0 -G1 X0.7862 Y8.6575 -G1 X0.7237 Y8.4654 -G3 X0.7206 Y8.4461 I0.0594 J-0.0193 -G3 X0.8199 Y8.3955 I0.0625 J0 -G1 X0.9833 Y8.5143 -G1 X1.1467 Y8.3955 -G3 X1.2459 Y8.4461 I0.0367 J0.0506 -G3 X1.2428 Y8.4654 I-0.0625 J0 -G1 X1.1805 Y8.6575 -G1 X1.3439 Y8.7762 -G3 X1.3697 Y8.8268 I-0.0367 J0.0506 -G3 X1.3072 Y8.8893 I-0.0625 J0 -G1 X1.1021 Y8.8893 -G0 Z0.25 -G0 X6.7974 Y8.3503 -G1 Z-0.05 F30 -G1 X6.7383 Y8.5415 F10 -G3 X6.6191 Y8.5423 I-0.0597 J-0.0185 -G1 X6.5567 Y8.3503 -G1 X6.3548 Y8.3503 -G3 X6.2923 Y8.2878 I0 J-0.0625 -G3 X6.3181 Y8.2372 I0.0625 J0 -G1 X6.4814 Y8.1185 -G1 X6.419 Y7.9264 -G3 X6.4159 Y7.9071 I0.0594 J-0.0193 -G3 X6.5151 Y7.8565 I0.0625 J0 -G1 X6.6786 Y7.9752 -G1 X6.8421 Y7.8565 -G3 X6.9413 Y7.9071 I0.0367 J0.0506 -G3 X6.9383 Y7.9264 I-0.0625 J0 -G1 X6.8758 Y8.1185 -G1 X7.0392 Y8.2372 -G3 X7.0649 Y8.2878 I-0.0367 J0.0506 -G3 X7.0024 Y8.3503 I-0.0625 J0 -G1 X6.7974 Y8.3503 -G0 Z0.25 -G0 X3.0006 Y9.4285 -G1 Z-0.05 F30 -G1 X2.9414 Y9.6197 F10 -G3 X2.8223 Y9.6205 I-0.0597 J-0.0185 -G1 X2.7599 Y9.4285 -G1 X2.5578 Y9.4285 -G3 X2.4953 Y9.366 I0 J-0.0625 -G3 X2.5211 Y9.3154 I0.0625 J0 -G1 X2.6845 Y9.1967 -G1 X2.6222 Y9.0046 -G3 X2.6191 Y8.9853 I0.0594 J-0.0193 -G3 X2.7183 Y8.9347 I0.0625 J0 -G1 X2.8817 Y9.0534 -G1 X3.0451 Y8.9347 -G3 X3.1444 Y8.9853 I0.0367 J0.0506 -G3 X3.1413 Y9.0046 I-0.0625 J0 -G1 X3.079 Y9.1967 -G1 X3.2424 Y9.3154 -G3 X3.2681 Y9.366 I-0.0367 J0.0506 -G3 X3.2056 Y9.4285 I-0.0625 J0 -G1 X3.0006 Y9.4285 -G0 Z0.25 -G0 X1.7349 Y9.4285 -G1 Z-0.05 F30 -G1 X1.6758 Y9.6197 F10 -G3 X1.5566 Y9.6205 I-0.0597 J-0.0185 -G1 X1.4942 Y9.4285 -G1 X1.2923 Y9.4285 -G3 X1.2298 Y9.366 I0 J-0.0625 -G3 X1.2556 Y9.3154 I0.0625 J0 -G1 X1.4189 Y9.1967 -G1 X1.3565 Y9.0046 -G3 X1.3534 Y8.9853 I0.0594 J-0.0193 -G3 X1.4526 Y8.9347 I0.0625 J0 -G1 X1.6161 Y9.0534 -G1 X1.7796 Y8.9347 -G3 X1.8788 Y8.9853 I0.0367 J0.0506 -G3 X1.8758 Y9.0046 I-0.0625 J0 -G1 X1.8133 Y9.1967 -G1 X1.9767 Y9.3154 -G3 X2.0024 Y9.366 I-0.0367 J0.0506 -G3 X1.9399 Y9.4285 I-0.0625 J0 -G1 X1.7349 Y9.4285 -G0 Z0.25 -G0 X4.2662 Y6.194 -G1 Z-0.05 F30 -G1 X4.207 Y6.3853 F10 -G3 X4.0878 Y6.3861 I-0.0597 J-0.0185 -G1 X4.0255 Y6.194 -G1 X3.8235 Y6.194 -G3 X3.761 Y6.1315 I0 J-0.0625 -G3 X3.7868 Y6.081 I0.0625 J0 -G1 X3.9502 Y5.9622 -G1 X3.8877 Y5.7702 -G3 X3.8847 Y5.7508 I0.0594 J-0.0193 -G3 X3.9839 Y5.7003 I0.0625 J0 -G1 X4.1473 Y5.819 -G1 X4.3108 Y5.7002 -G3 X4.4101 Y5.7508 I0.0367 J0.0506 -G3 X4.407 Y5.7702 I-0.0625 J0 -G1 X4.3445 Y5.9622 -G1 X4.5079 Y6.081 -G3 X4.5337 Y6.1315 I-0.0367 J0.0506 -G3 X4.4712 Y6.194 I-0.0625 J0 -G1 X4.2662 Y6.194 -G0 Z0.25 -G0 X3.0006 Y6.194 -G1 Z-0.05 F30 -G1 X2.9414 Y6.3853 F10 -G3 X2.8223 Y6.3861 I-0.0597 J-0.0185 -G1 X2.7599 Y6.194 -G1 X2.5578 Y6.194 -G3 X2.4953 Y6.1315 I0 J-0.0625 -G3 X2.5211 Y6.081 I0.0625 J0 -G1 X2.6845 Y5.9622 -G1 X2.6222 Y5.7701 -G3 X2.6191 Y5.7508 I0.0594 J-0.0193 -G3 X2.7183 Y5.7003 I0.0625 J0 -G1 X2.8817 Y5.819 -G1 X3.0451 Y5.7003 -G3 X3.1444 Y5.7508 I0.0367 J0.0506 -G3 X3.1413 Y5.7701 I-0.0625 J0 -G1 X3.079 Y5.9622 -G1 X3.2424 Y6.081 -G3 X3.2681 Y6.1315 I-0.0367 J0.0506 -G3 X3.2056 Y6.194 I-0.0625 J0 -G1 X3.0006 Y6.194 -G0 Z0.25 -G0 X6.1646 Y8.8893 -G1 Z-0.05 F30 -G1 X6.1055 Y9.0805 F10 -G3 X5.9863 Y9.0814 I-0.0597 J-0.0185 -G1 X5.924 Y8.8893 -G1 X5.722 Y8.8893 -G3 X5.6595 Y8.8268 I0 J-0.0625 -G3 X5.6853 Y8.7762 I0.0625 J0 -G1 X5.8487 Y8.6575 -G1 X5.7862 Y8.4654 -G3 X5.7831 Y8.4461 I0.0594 J-0.0193 -G3 X5.8824 Y8.3955 I0.0625 J0 -G1 X6.0458 Y8.5143 -G1 X6.2092 Y8.3955 -G3 X6.3084 Y8.4461 I0.0367 J0.0506 -G3 X6.3053 Y8.4654 I-0.0625 J0 -G1 X6.243 Y8.6575 -G1 X6.4064 Y8.7762 -G3 X6.4322 Y8.8268 I-0.0367 J0.0506 -G3 X6.3697 Y8.8893 I-0.0625 J0 -G1 X6.1646 Y8.8893 -G0 Z0.25 -G0 X5.5319 Y9.4285 -G1 Z-0.05 F30 -G1 X5.4727 Y9.6197 F10 -G3 X5.3535 Y9.6205 I-0.0597 J-0.0185 -G1 X5.2912 Y9.4285 -G1 X5.0891 Y9.4285 -G3 X5.0266 Y9.366 I0 J-0.0625 -G3 X5.0524 Y9.3154 I0.0625 J0 -G1 X5.2158 Y9.1967 -G1 X5.1534 Y9.0046 -G3 X5.1503 Y8.9853 I0.0594 J-0.0193 -G3 X5.2496 Y8.9347 I0.0625 J0 -G1 X5.413 Y9.0534 -G1 X5.5764 Y8.9347 -G3 X5.6756 Y8.9853 I0.0367 J0.0506 -G3 X5.6726 Y9.0046 I-0.0625 J0 -G1 X5.6102 Y9.1967 -G1 X5.7736 Y9.3154 -G3 X5.7994 Y9.366 I-0.0367 J0.0506 -G3 X5.7369 Y9.4285 I-0.0625 J0 -G1 X5.5319 Y9.4285 -G0 Z0.25 -G0 X5.5319 Y7.2722 -G1 Z-0.05 F30 -G1 X5.4727 Y7.4635 F10 -G3 X5.3535 Y7.4643 I-0.0597 J-0.0185 -G1 X5.2912 Y7.2722 -G1 X5.0891 Y7.2722 -G3 X5.0266 Y7.2097 I0 J-0.0625 -G3 X5.0524 Y7.1591 I0.0625 J0 -G1 X5.2158 Y7.0404 -G1 X5.1534 Y6.8483 -G3 X5.1503 Y6.829 I0.0594 J-0.0193 -G3 X5.2496 Y6.7785 I0.0625 J0 -G1 X5.413 Y6.8972 -G1 X5.5764 Y6.7785 -G3 X5.6756 Y6.829 I0.0367 J0.0506 -G3 X5.6726 Y6.8483 I-0.0625 J0 -G1 X5.6102 Y7.0404 -G1 X5.7736 Y7.1591 -G3 X5.7994 Y7.2097 I-0.0367 J0.0506 -G3 X5.7369 Y7.2722 I-0.0625 J0 -G1 X5.5319 Y7.2722 -G0 Z0.25 -G0 X6.1646 Y7.8124 -G1 Z-0.05 F30 -G1 X6.1055 Y8.0037 F10 -G3 X5.9863 Y8.0046 I-0.0597 J-0.0185 -G1 X5.9239 Y7.8124 -G1 X5.722 Y7.8124 -G3 X5.6595 Y7.7499 I0 J-0.0625 -G3 X5.6853 Y7.6993 I0.0625 J0 -G1 X5.8487 Y7.5806 -G1 X5.7862 Y7.3885 -G3 X5.7831 Y7.3692 I0.0594 J-0.0193 -G3 X5.8824 Y7.3186 I0.0625 J0 -G1 X6.0458 Y7.4373 -G1 X6.2092 Y7.3186 -G3 X6.3084 Y7.3692 I0.0367 J0.0506 -G3 X6.3053 Y7.3885 I-0.0625 J0 -G1 X6.243 Y7.5806 -G1 X6.4064 Y7.6993 -G3 X6.4322 Y7.7499 I-0.0367 J0.0506 -G3 X6.3697 Y7.8124 I-0.0625 J0 -G1 X6.1646 Y7.8124 -G0 Z0.25 -G0 X1.1021 Y7.8124 -G1 Z-0.05 F30 -G1 X1.043 Y8.0037 F10 -G3 X0.9238 Y8.0046 I-0.0597 J-0.0185 -G1 X0.8614 Y7.8124 -G1 X0.6595 Y7.8124 -G3 X0.597 Y7.7499 I0 J-0.0625 -G3 X0.6228 Y7.6993 I0.0625 J0 -G1 X0.7862 Y7.5806 -G1 X0.7237 Y7.3885 -G3 X0.7206 Y7.3692 I0.0594 J-0.0193 -G3 X0.8199 Y7.3186 I0.0625 J0 -G1 X0.9833 Y7.4373 -G1 X1.1467 Y7.3186 -G3 X1.2459 Y7.3692 I0.0367 J0.0506 -G3 X1.2428 Y7.3885 I-0.0625 J0 -G1 X1.1805 Y7.5806 -G1 X1.3439 Y7.6993 -G3 X1.3697 Y7.7499 I-0.0367 J0.0506 -G3 X1.3072 Y7.8124 I-0.0625 J0 -G1 X1.1021 Y7.8124 -G0 Z0.25 -G0 X3.6334 Y7.8124 -G1 Z-0.05 F30 -G1 X3.5742 Y8.0037 F10 -G3 X3.4551 Y8.0046 I-0.0597 J-0.0185 -G1 X3.3927 Y7.8124 -G1 X3.1908 Y7.8124 -G3 X3.1283 Y7.7499 I0 J-0.0625 -G3 X3.154 Y7.6993 I0.0625 J0 -G1 X3.3174 Y7.5806 -G1 X3.2549 Y7.3885 -G3 X3.2519 Y7.3692 I0.0594 J-0.0193 -G3 X3.3511 Y7.3186 I0.0625 J0 -G1 X3.5145 Y7.4373 -G1 X3.6779 Y7.3186 -G3 X3.7772 Y7.3692 I0.0367 J0.0506 -G3 X3.7741 Y7.3885 I-0.0625 J0 -G1 X3.7117 Y7.5806 -G1 X3.8751 Y7.6993 -G3 X3.9009 Y7.7499 I-0.0367 J0.0506 -G3 X3.8384 Y7.8124 I-0.0625 J0 -G1 X3.6334 Y7.8124 -G0 Z0.25 -G0 X7.4302 Y8.8893 -G1 Z-0.05 F30 -G1 X7.3712 Y9.0805 F10 -G3 X7.252 Y9.0814 I-0.0597 J-0.0184 -G1 X7.1895 Y8.8893 -G1 X6.9876 Y8.8893 -G3 X6.9251 Y8.8268 I0 J-0.0625 -G3 X6.9508 Y8.7762 I0.0625 J0 -G1 X7.1142 Y8.6575 -G1 X7.0519 Y8.4654 -G3 X7.0488 Y8.4461 I0.0594 J-0.0193 -G3 X7.1481 Y8.3955 I0.0625 J0 -G1 X7.3115 Y8.5143 -G1 X7.4749 Y8.3955 -G3 X7.5741 Y8.4461 I0.0367 J0.0506 -G3 X7.571 Y8.4654 I-0.0625 J0 -G1 X7.5086 Y8.6575 -G1 X7.6719 Y8.7762 -G3 X7.6977 Y8.8268 I-0.0367 J0.0506 -G3 X7.6352 Y8.8893 I-0.0625 J0 -G1 X7.4302 Y8.8893 -G0 Z0.25 -G0 X2.3677 Y8.8893 -G1 Z-0.05 F30 -G1 X2.3087 Y9.0805 F10 -G3 X2.1895 Y9.0814 I-0.0597 J-0.0184 -G1 X2.127 Y8.8893 -G1 X1.9251 Y8.8893 -G3 X1.8626 Y8.8268 I0 J-0.0625 -G3 X1.8883 Y8.7762 I0.0625 J0 -G1 X2.0517 Y8.6575 -G1 X1.9894 Y8.4654 -G3 X1.9863 Y8.4461 I0.0594 J-0.0193 -G3 X2.0856 Y8.3955 I0.0625 J0 -G1 X2.249 Y8.5143 -G1 X2.4124 Y8.3955 -G3 X2.5116 Y8.4461 I0.0367 J0.0506 -G3 X2.5085 Y8.4654 I-0.0625 J0 -G1 X2.4461 Y8.6575 -G1 X2.6094 Y8.7762 -G3 X2.6352 Y8.8268 I-0.0367 J0.0506 -G3 X2.5727 Y8.8893 I-0.0625 J0 -G1 X2.3677 Y8.8893 -G0 Z0.25 -G0 X2.3677 Y6.733 -G1 Z-0.05 F30 -G1 X2.3087 Y6.9243 F10 -G3 X2.1895 Y6.9252 I-0.0597 J-0.0184 -G1 X2.127 Y6.733 -G1 X1.9251 Y6.733 -G3 X1.8626 Y6.6705 I0 J-0.0625 -G3 X1.8883 Y6.62 I0.0625 J0 -G1 X2.0517 Y6.5013 -G1 X1.9894 Y6.3092 -G3 X1.9863 Y6.2899 I0.0594 J-0.0193 -G3 X2.0856 Y6.2393 I0.0625 J0 -G1 X2.249 Y6.358 -G1 X2.4124 Y6.2393 -G3 X2.5116 Y6.2899 I0.0367 J0.0506 -G3 X2.5085 Y6.3092 I-0.0625 J0 -G1 X2.4461 Y6.5013 -G1 X2.6094 Y6.62 -G3 X2.6352 Y6.6705 I-0.0367 J0.0506 -G3 X2.5727 Y6.733 I-0.0625 J0 -G1 X2.3677 Y6.733 -G0 Z0.25 -G0 X4.899 Y6.733 -G1 Z-0.05 F30 -G1 X4.8399 Y6.9243 F10 -G3 X4.7208 Y6.9252 I-0.0597 J-0.0184 -G1 X4.6583 Y6.733 -G1 X4.4563 Y6.733 -G3 X4.3938 Y6.6705 I0 J-0.0625 -G3 X4.4196 Y6.62 I0.0625 J0 -G1 X4.583 Y6.5013 -G1 X4.5206 Y6.3092 -G3 X4.5176 Y6.2899 I0.0594 J-0.0193 -G3 X4.6168 Y6.2393 I0.0625 J0 -G1 X4.7802 Y6.358 -G1 X4.9436 Y6.2393 -G3 X5.0428 Y6.2899 I0.0367 J0.0506 -G3 X5.0398 Y6.3092 I-0.0625 J0 -G1 X4.9773 Y6.5013 -G1 X5.1407 Y6.62 -G3 X5.1665 Y6.6705 I-0.0367 J0.0506 -G3 X5.104 Y6.733 I-0.0625 J0 -G1 X4.899 Y6.733 -G0 Z0.25 -G0 X4.899 Y8.8893 -G1 Z-0.05 F30 -G1 X4.8399 Y9.0805 F10 -G3 X4.7208 Y9.0814 I-0.0597 J-0.0184 -G1 X4.6583 Y8.8893 -G1 X4.4563 Y8.8893 -G3 X4.3938 Y8.8268 I0 J-0.0625 -G3 X4.4196 Y8.7762 I0.0625 J0 -G1 X4.583 Y8.6575 -G1 X4.5206 Y8.4654 -G3 X4.5176 Y8.4461 I0.0594 J-0.0193 -G3 X4.6168 Y8.3955 I0.0625 J0 -G1 X4.7802 Y8.5143 -G1 X4.9436 Y8.3955 -G3 X5.0428 Y8.4461 I0.0367 J0.0506 -G3 X5.0398 Y8.4654 I-0.0625 J0 -G1 X4.9773 Y8.6575 -G1 X5.1407 Y8.7762 -G3 X5.1665 Y8.8268 I-0.0367 J0.0506 -G3 X5.104 Y8.8893 I-0.0625 J0 -G1 X4.899 Y8.8893 -G0 Z0.25 -G0 X1.7349 Y6.194 -G1 Z-0.05 F30 -G1 X1.6759 Y6.3852 F10 -G3 X1.5567 Y6.3861 I-0.0597 J-0.0184 -G1 X1.4943 Y6.194 -G1 X1.2923 Y6.194 -G3 X1.2298 Y6.1315 I0 J-0.0625 -G3 X1.2556 Y6.081 I0.0625 J0 -G1 X1.4189 Y5.9622 -G1 X1.3565 Y5.7702 -G3 X1.3534 Y5.7508 I0.0594 J-0.0193 -G3 X1.4526 Y5.7002 I0.0625 J0 -G1 X1.6162 Y5.819 -G1 X1.7796 Y5.7003 -G3 X1.8788 Y5.7508 I0.0367 J0.0506 -G3 X1.8758 Y5.7702 I-0.0625 J0 -G1 X1.8133 Y5.9622 -G1 X1.9767 Y6.081 -G3 X2.0024 Y6.1315 I-0.0367 J0.0506 -G3 X1.9399 Y6.194 I-0.0625 J0 -G1 X1.7349 Y6.194 -G0 Z0.25 -G0 X1.7349 Y8.3503 -G1 Z-0.05 F30 -G1 X1.6759 Y8.5415 F10 -G3 X1.5567 Y8.5424 I-0.0597 J-0.0184 -G1 X1.4943 Y8.3503 -G1 X1.2923 Y8.3503 -G3 X1.2298 Y8.2878 I0 J-0.0625 -G3 X1.2556 Y8.2372 I0.0625 J0 -G1 X1.4189 Y8.1185 -G1 X1.3565 Y7.9264 -G3 X1.3534 Y7.9071 I0.0594 J-0.0193 -G3 X1.4526 Y7.8565 I0.0625 J0 -G1 X1.6162 Y7.9752 -G1 X1.7796 Y7.8565 -G3 X1.8788 Y7.9071 I0.0367 J0.0506 -G3 X1.8758 Y7.9264 I-0.0625 J0 -G1 X1.8133 Y8.1185 -G1 X1.9767 Y8.2372 -G3 X2.0024 Y8.2878 I-0.0367 J0.0506 -G3 X1.9399 Y8.3503 I-0.0625 J0 -G1 X1.7349 Y8.3503 -G0 Z0.25 -G0 X7.4302 Y6.733 -G1 Z-0.05 F30 -G1 X7.3712 Y6.9243 F10 -G3 X7.252 Y6.9252 I-0.0597 J-0.0184 -G1 X7.1895 Y6.733 -G1 X6.9876 Y6.733 -G3 X6.9251 Y6.6705 I0 J-0.0625 -G3 X6.9508 Y6.62 I0.0625 J0 -G1 X7.1142 Y6.5013 -G1 X7.0519 Y6.3092 -G3 X7.0488 Y6.2899 I0.0594 J-0.0193 -G3 X7.1481 Y6.2393 I0.0625 J0 -G1 X7.3115 Y6.358 -G1 X7.4749 Y6.2393 -G3 X7.5741 Y6.2899 I0.0367 J0.0506 -G3 X7.571 Y6.3092 I-0.0625 J0 -G1 X7.5086 Y6.5013 -G1 X7.6719 Y6.62 -G3 X7.6977 Y6.6705 I-0.0367 J0.0506 -G3 X7.6352 Y6.733 I-0.0625 J0 -G1 X7.4302 Y6.733 -G0 Z0.25 -G0 X7.4302 Y7.8124 -G1 Z-0.05 F30 -G1 X7.3712 Y8.0037 F10 -G3 X7.252 Y8.0046 I-0.0597 J-0.0184 -G1 X7.1895 Y7.8124 -G1 X6.9876 Y7.8124 -G3 X6.9251 Y7.7499 I0 J-0.0625 -G3 X6.9508 Y7.6993 I0.0625 J0 -G1 X7.1142 Y7.5806 -G1 X7.0519 Y7.3885 -G3 X7.0488 Y7.3692 I0.0594 J-0.0193 -G3 X7.1481 Y7.3186 I0.0625 J0 -G1 X7.3115 Y7.4373 -G1 X7.4749 Y7.3186 -G3 X7.5741 Y7.3692 I0.0367 J0.0506 -G3 X7.571 Y7.3885 I-0.0625 J0 -G1 X7.5086 Y7.5806 -G1 X7.6719 Y7.6993 -G3 X7.6977 Y7.7499 I-0.0367 J0.0506 -G3 X7.6352 Y7.8124 I-0.0625 J0 -G1 X7.4302 Y7.8124 -G0 Z0.25 -G0 X4.899 Y7.8124 -G1 Z-0.05 F30 -G1 X4.8399 Y8.0037 F10 -G3 X4.7208 Y8.0046 I-0.0597 J-0.0184 -G1 X4.6583 Y7.8124 -G1 X4.4563 Y7.8124 -G3 X4.3938 Y7.7499 I0 J-0.0625 -G3 X4.4196 Y7.6993 I0.0625 J0 -G1 X4.583 Y7.5806 -G1 X4.5206 Y7.3885 -G3 X4.5176 Y7.3692 I0.0594 J-0.0193 -G3 X4.6168 Y7.3186 I0.0625 J0 -G1 X4.7802 Y7.4373 -G1 X4.9436 Y7.3186 -G3 X5.0428 Y7.3692 I0.0367 J0.0506 -G3 X5.0398 Y7.3885 I-0.0625 J0 -G1 X4.9773 Y7.5806 -G1 X5.1407 Y7.6993 -G3 X5.1665 Y7.7499 I-0.0367 J0.0506 -G3 X5.104 Y7.8124 I-0.0625 J0 -G1 X4.899 Y7.8124 -G0 Z0.25 -G0 X2.3677 Y7.8124 -G1 Z-0.05 F30 -G1 X2.3087 Y8.0037 F10 -G3 X2.1895 Y8.0046 I-0.0597 J-0.0184 -G1 X2.127 Y7.8124 -G1 X1.9251 Y7.8124 -G3 X1.8626 Y7.7499 I0 J-0.0625 -G3 X1.8883 Y7.6993 I0.0625 J0 -G1 X2.0517 Y7.5806 -G1 X1.9894 Y7.3885 -G3 X1.9863 Y7.3692 I0.0594 J-0.0193 -G3 X2.0856 Y7.3186 I0.0625 J0 -G1 X2.249 Y7.4373 -G1 X2.4124 Y7.3186 -G3 X2.5116 Y7.3692 I0.0367 J0.0506 -G3 X2.5085 Y7.3885 I-0.0625 J0 -G1 X2.4461 Y7.5806 -G1 X2.6094 Y7.6993 -G3 X2.6352 Y7.7499 I-0.0367 J0.0506 -G3 X2.5727 Y7.8124 I-0.0625 J0 -G1 X2.3677 Y7.8124 -G0 Z0.25 -G0 X4.207 Y9.9883 -G1 Z-0.05 F30 -G1 X4.0877 Y9.9883 F10 -G2 X4.1009 Y9.9061 I-0.2493 J-0.0822 -G2 X4.0966 Y9.8588 I-0.2625 J0 -G2 X4.1981 Y9.8588 I0.0507 J-0.2576 -G2 X4.1938 Y9.9061 I0.2582 J0.0473 -G2 X4.207 Y9.9883 I0.2625 J0 -G1 X4.2438 Y9.9061 F10 -G2 X4.29 Y10.0383 I0.2125 J0 F10 -G1 X4.0048 Y10.0383 -G2 X4.0509 Y9.9061 I-0.1664 J-0.1322 -G2 X3.9633 Y9.7342 I-0.2125 J0 -G1 X3.888 Y9.6795 -G1 X3.9168 Y9.591 -G2 X3.9186 Y9.585 I-0.2021 J-0.0656 -G1 X3.9452 Y9.6669 -G2 X4.3503 Y9.664 I0.2021 J-0.0656 -G1 X4.3754 Y9.5827 -G2 X4.378 Y9.591 I0.2046 J-0.0573 -G1 X4.4067 Y9.6795 -G1 X4.3314 Y9.7342 -G2 X4.2438 Y9.9061 I0.1249 J0.1719 -G1 X4.2938 Y9.9061 F10 -G2 X4.4563 Y10.0686 I0.1625 J0 F10 -G1 X4.5856 Y10.0686 -G1 X4.592 Y10.0883 -G1 X3.701 Y10.0883 -G1 X3.7071 Y10.0686 -G1 X3.8384 Y10.0686 -G2 X4.0009 Y9.9061 I0 J-0.1625 -G2 X3.9339 Y9.7746 I-0.1625 J0 -G1 X3.8293 Y9.6986 -G1 X3.8692 Y9.5756 -G2 X3.8771 Y9.5285 I-0.1546 J-0.0502 -G1 X3.9528 Y9.5285 -G1 X3.9927 Y9.6514 -G2 X4.3025 Y9.6493 I0.1546 J-0.0502 -G1 X4.3399 Y9.5285 -G1 X4.4176 Y9.5285 -G2 X4.4255 Y9.5756 I0.1625 J-0.0031 -G1 X4.4655 Y9.6986 -G1 X4.3608 Y9.7746 -G2 X4.2938 Y9.9061 I0.0955 J0.1315 -G1 X4.3438 Y9.9061 F10 -G2 X4.4563 Y10.0186 I0.1125 J0 F10 -G1 X4.622 Y10.0186 -G1 X4.6609 Y10.1383 -G1 X3.6333 Y10.1383 -G1 X3.6703 Y10.0186 -G1 X3.8384 Y10.0186 -G2 X3.9509 Y9.9061 I0 J-0.1125 -G2 X3.9045 Y9.8151 I-0.1125 J0 -G1 X3.7705 Y9.7177 -G1 X3.8217 Y9.5601 -G2 X3.8272 Y9.5254 I-0.107 J-0.0347 -G2 X3.8168 Y9.4783 I-0.1125 J0 -G2 X3.8235 Y9.4785 I0.0067 J-0.1123 -G1 X3.9891 Y9.4785 -G1 X4.0403 Y9.636 -G2 X4.2548 Y9.6345 I0.107 J-0.0347 -G1 X4.303 Y9.4785 -G1 X4.4712 Y9.4785 -G2 X4.4779 Y9.4783 I0 J-0.1125 -G2 X4.4676 Y9.5254 I0.1021 J0.0471 -G2 X4.4731 Y9.5601 I0.1125 J0 -G1 X4.5242 Y9.7177 -G1 X4.3902 Y9.8151 -G2 X4.3438 Y9.9061 I0.0661 J0.091 -G0 Z0.25 -G0 X1.6758 Y9.9883 -G1 Z-0.05 F30 -G1 X1.5564 Y9.9883 F10 -G2 X1.5697 Y9.9061 I-0.2493 J-0.0822 -G2 X1.5654 Y9.8588 I-0.2625 J0 -G2 X1.6669 Y9.8588 I0.0507 J-0.2576 -G2 X1.6626 Y9.9061 I0.2582 J0.0473 -G2 X1.6758 Y9.9883 I0.2625 J0 -G1 X1.7126 Y9.9061 F10 -G2 X1.7587 Y10.0383 I0.2125 J0 F10 -G1 X1.4735 Y10.0383 -G2 X1.5197 Y9.9061 I-0.1664 J-0.1322 -G2 X1.4321 Y9.7342 I-0.2125 J0 -G1 X1.3568 Y9.6795 -G1 X1.3855 Y9.591 -G2 X1.3874 Y9.585 I-0.2021 J-0.0656 -G1 X1.4139 Y9.6669 -G2 X1.8191 Y9.664 I0.2021 J-0.0656 -G1 X1.8442 Y9.5827 -G2 X1.8467 Y9.591 I0.2046 J-0.0573 -G1 X1.8754 Y9.6795 -G1 X1.8002 Y9.7342 -G2 X1.7126 Y9.9061 I0.1249 J0.1719 -G1 X1.7626 Y9.9061 F10 -G2 X1.9251 Y10.0686 I0.1625 J0 F10 -G1 X2.0544 Y10.0686 -G1 X2.0608 Y10.0883 -G1 X1.1698 Y10.0883 -G1 X1.1759 Y10.0686 -G1 X1.3072 Y10.0686 -G2 X1.4697 Y9.9061 I0 J-0.1625 -G2 X1.4027 Y9.7746 I-0.1625 J0 -G1 X1.298 Y9.6986 -G1 X1.338 Y9.5756 -G2 X1.3459 Y9.5285 I-0.1546 J-0.0502 -G1 X1.4216 Y9.5285 -G1 X1.4615 Y9.6514 -G2 X1.7713 Y9.6493 I0.1546 J-0.0502 -G1 X1.8087 Y9.5285 -G1 X1.8863 Y9.5285 -G2 X1.8943 Y9.5756 I0.1625 J-0.0031 -G1 X1.9342 Y9.6986 -G1 X1.8296 Y9.7746 -G2 X1.7626 Y9.9061 I0.0955 J0.1315 -G1 X1.8126 Y9.9061 F10 -G2 X1.9251 Y10.0186 I0.1125 J0 F10 -G1 X2.0907 Y10.0186 -G1 X2.1296 Y10.1383 -G1 X1.102 Y10.1383 -G1 X1.139 Y10.0186 -G1 X1.3072 Y10.0186 -G2 X1.4197 Y9.9061 I0 J-0.1125 -G2 X1.3733 Y9.8151 I-0.1125 J0 -G1 X1.2392 Y9.7177 -G1 X1.2904 Y9.5601 -G2 X1.2959 Y9.5254 I-0.107 J-0.0347 -G2 X1.2855 Y9.4783 I-0.1125 J0 -G2 X1.2923 Y9.4785 I0.0067 J-0.1123 -G1 X1.4579 Y9.4785 -G1 X1.509 Y9.636 -G2 X1.7235 Y9.6345 I0.107 J-0.0347 -G1 X1.7718 Y9.4785 -G1 X1.9399 Y9.4785 -G2 X1.9467 Y9.4783 I0 J-0.1125 -G2 X1.9363 Y9.5254 I0.1021 J0.0471 -G2 X1.9418 Y9.5601 I0.1125 J0 -G1 X1.993 Y9.7177 -G1 X1.8589 Y9.8151 -G2 X1.8126 Y9.9061 I0.0661 J0.091 -G0 Z0.25 -G0 X6.7383 Y9.9883 -G1 Z-0.05 F30 -G1 X6.6189 Y9.9883 F10 -G2 X6.6322 Y9.9061 I-0.2493 J-0.0822 -G2 X6.6279 Y9.8588 I-0.2625 J0 -G2 X6.7294 Y9.8588 I0.0507 J-0.2576 -G2 X6.7251 Y9.9061 I0.2582 J0.0473 -G2 X6.7383 Y9.9883 I0.2625 J0 -G1 X6.7751 Y9.9061 F10 -G2 X6.8212 Y10.0383 I0.2125 J0 F10 -G1 X6.536 Y10.0383 -G2 X6.5822 Y9.9061 I-0.1664 J-0.1322 -G2 X6.4946 Y9.7342 I-0.2125 J0 -G1 X6.4193 Y9.6795 -G1 X6.448 Y9.591 -G2 X6.4499 Y9.585 I-0.2021 J-0.0656 -G1 X6.4764 Y9.6669 -G2 X6.8816 Y9.664 I0.2021 J-0.0656 -G1 X6.9067 Y9.5827 -G2 X6.9092 Y9.591 I0.2046 J-0.0573 -G1 X6.9379 Y9.6795 -G1 X6.8627 Y9.7342 -G2 X6.7751 Y9.9061 I0.1249 J0.1719 -G1 X6.8251 Y9.9061 F10 -G2 X6.9876 Y10.0686 I0.1625 J0 F10 -G1 X7.1169 Y10.0686 -G1 X7.1233 Y10.0883 -G1 X6.2323 Y10.0883 -G1 X6.2384 Y10.0686 -G1 X6.3697 Y10.0686 -G2 X6.5322 Y9.9061 I0 J-0.1625 -G2 X6.4652 Y9.7746 I-0.1625 J0 -G1 X6.3605 Y9.6986 -G1 X6.4005 Y9.5756 -G2 X6.4084 Y9.5285 I-0.1546 J-0.0502 -G1 X6.4841 Y9.5285 -G1 X6.524 Y9.6514 -G2 X6.8338 Y9.6493 I0.1546 J-0.0502 -G1 X6.8712 Y9.5285 -G1 X6.9488 Y9.5285 -G2 X6.9568 Y9.5756 I0.1625 J-0.0031 -G1 X6.9967 Y9.6986 -G1 X6.8921 Y9.7746 -G2 X6.8251 Y9.9061 I0.0955 J0.1315 -G1 X6.8751 Y9.9061 F10 -G2 X6.9876 Y10.0186 I0.1125 J0 F10 -G1 X7.1532 Y10.0186 -G1 X7.1921 Y10.1383 -G1 X6.1645 Y10.1383 -G1 X6.2015 Y10.0186 -G1 X6.3697 Y10.0186 -G2 X6.4822 Y9.9061 I0 J-0.1125 -G2 X6.4358 Y9.8151 I-0.1125 J0 -G1 X6.3017 Y9.7177 -G1 X6.3529 Y9.5601 -G2 X6.3584 Y9.5254 I-0.107 J-0.0347 -G2 X6.348 Y9.4783 I-0.1125 J0 -G2 X6.3548 Y9.4785 I0.0067 J-0.1123 -G1 X6.5204 Y9.4785 -G1 X6.5715 Y9.636 -G2 X6.786 Y9.6345 I0.107 J-0.0347 -G1 X6.8343 Y9.4785 -G1 X7.0024 Y9.4785 -G2 X7.0092 Y9.4783 I0 J-0.1125 -G2 X6.9988 Y9.5254 I0.1021 J0.0471 -G2 X7.0043 Y9.5601 I0.1125 J0 -G1 X7.0555 Y9.7177 -G1 X6.9214 Y9.8151 -G2 X6.8751 Y9.9061 I0.0661 J0.091 -G0 Z0.25 -G0 X2.9415 Y9.9883 -G1 Z-0.05 F30 -G1 X2.822 Y9.9883 F10 -G2 X2.8352 Y9.9061 I-0.2493 J-0.0822 -G2 X2.8309 Y9.8588 I-0.2625 J0 -G2 X2.9326 Y9.8588 I0.0508 J-0.2575 -G2 X2.9283 Y9.9061 I0.2582 J0.0473 -G2 X2.9415 Y9.9883 I0.2625 J0 -G1 X2.9783 Y9.9061 F10 -G2 X3.0244 Y10.0383 I0.2125 J0 F10 -G1 X2.7391 Y10.0383 -G2 X2.7852 Y9.9061 I-0.1664 J-0.1322 -G2 X2.6976 Y9.7342 I-0.2125 J0 -G1 X2.6224 Y9.6796 -G1 X2.6512 Y9.5911 -G2 X2.6531 Y9.585 I-0.2021 J-0.0657 -G1 X2.6796 Y9.6669 -G2 X3.0847 Y9.664 I0.2021 J-0.0656 -G1 X3.1098 Y9.583 -G2 X3.1123 Y9.5911 I0.2046 J-0.0576 -G1 X3.1411 Y9.6796 -G1 X3.0659 Y9.7342 -G2 X2.9783 Y9.9061 I0.1249 J0.1719 -G1 X3.0283 Y9.9061 F10 -G2 X3.1908 Y10.0686 I0.1625 J0 F10 -G1 X3.32 Y10.0686 -G1 X3.3264 Y10.0883 -G1 X2.4354 Y10.0883 -G1 X2.4415 Y10.0686 -G1 X2.5727 Y10.0686 -G2 X2.7352 Y9.9061 I0 J-0.1625 -G2 X2.6682 Y9.7746 I-0.1625 J0 -G1 X2.5636 Y9.6986 -G1 X2.6036 Y9.5757 -G2 X2.6116 Y9.5285 I-0.1545 J-0.0503 -G1 X2.6873 Y9.5285 -G1 X2.7272 Y9.6514 -G2 X3.037 Y9.6493 I0.1546 J-0.0502 -G1 X3.0743 Y9.5285 -G1 X3.1519 Y9.5285 -G2 X3.1598 Y9.5757 I0.1625 J-0.0031 -G1 X3.1998 Y9.6986 -G1 X3.0952 Y9.7746 -G2 X3.0283 Y9.9061 I0.0955 J0.1315 -G1 X3.0783 Y9.9061 F10 -G2 X3.1908 Y10.0186 I0.1125 J0 F10 -G1 X3.3564 Y10.0186 -G1 X3.3952 Y10.1383 -G1 X2.3677 Y10.1383 -G1 X2.4046 Y10.0186 -G1 X2.5727 Y10.0186 -G2 X2.6852 Y9.9061 I0 J-0.1125 -G2 X2.6388 Y9.8151 I-0.1125 J0 -G1 X2.5048 Y9.7177 -G1 X2.5561 Y9.5602 -G2 X2.5616 Y9.5254 I-0.107 J-0.0348 -G2 X2.5512 Y9.4783 I-0.1125 J0 -G2 X2.5578 Y9.4785 I0.0066 J-0.1123 -G1 X2.7236 Y9.4785 -G1 X2.7747 Y9.636 -G2 X2.9892 Y9.6345 I0.107 J-0.0347 -G1 X3.0375 Y9.4785 -G1 X3.2056 Y9.4785 -G2 X3.2122 Y9.4783 I0 J-0.1125 -G2 X3.2019 Y9.5254 I0.1021 J0.0471 -G2 X3.2074 Y9.5602 I0.1125 J0 -G1 X3.2586 Y9.7177 -G1 X3.1246 Y9.8151 -G2 X3.0783 Y9.9061 I0.0661 J0.091 -G0 Z0.25 -G0 X5.4727 Y9.9883 -G1 Z-0.05 F30 -G1 X5.3532 Y9.9883 F10 -G2 X5.3665 Y9.9061 I-0.2493 J-0.0822 -G2 X5.3622 Y9.8588 I-0.2625 J0 -G2 X5.4638 Y9.8588 I0.0508 J-0.2575 -G2 X5.4595 Y9.9061 I0.2582 J0.0473 -G2 X5.4727 Y9.9883 I0.2625 J0 -G1 X5.5095 Y9.9061 F10 -G2 X5.5557 Y10.0383 I0.2125 J0 F10 -G1 X5.2703 Y10.0383 -G2 X5.3165 Y9.9061 I-0.1664 J-0.1322 -G2 X5.2289 Y9.7342 I-0.2125 J0 -G1 X5.1537 Y9.6796 -G1 X5.1824 Y9.5911 -G2 X5.1843 Y9.585 I-0.2021 J-0.0657 -G1 X5.2109 Y9.6669 -G2 X5.616 Y9.664 I0.2021 J-0.0656 -G1 X5.6411 Y9.583 -G2 X5.6435 Y9.5911 I0.2046 J-0.0576 -G1 X5.6723 Y9.6796 -G1 X5.5971 Y9.7342 -G2 X5.5095 Y9.9061 I0.1249 J0.1719 -G1 X5.5595 Y9.9061 F10 -G2 X5.722 Y10.0686 I0.1625 J0 F10 -G1 X5.8513 Y10.0686 -G1 X5.8577 Y10.0883 -G1 X4.9667 Y10.0883 -G1 X4.9728 Y10.0686 -G1 X5.104 Y10.0686 -G2 X5.2665 Y9.9061 I0 J-0.1625 -G2 X5.1995 Y9.7746 I-0.1625 J0 -G1 X5.0949 Y9.6986 -G1 X5.1349 Y9.5757 -G2 X5.1428 Y9.5285 I-0.1545 J-0.0503 -G1 X5.2185 Y9.5285 -G1 X5.2584 Y9.6514 -G2 X5.5682 Y9.6493 I0.1546 J-0.0502 -G1 X5.6056 Y9.5285 -G1 X5.6832 Y9.5285 -G2 X5.6911 Y9.5757 I0.1625 J-0.0031 -G1 X5.7311 Y9.6986 -G1 X5.6265 Y9.7746 -G2 X5.5595 Y9.9061 I0.0955 J0.1315 -G1 X5.6095 Y9.9061 F10 -G2 X5.722 Y10.0186 I0.1125 J0 F10 -G1 X5.8876 Y10.0186 -G1 X5.9265 Y10.1383 -G1 X4.8989 Y10.1383 -G1 X4.9359 Y10.0186 -G1 X5.104 Y10.0186 -G2 X5.2165 Y9.9061 I0 J-0.1125 -G2 X5.1701 Y9.8151 I-0.1125 J0 -G1 X5.0361 Y9.7177 -G1 X5.0873 Y9.5602 -G2 X5.0928 Y9.5254 I-0.107 J-0.0348 -G2 X5.0825 Y9.4783 I-0.1125 J0 -G2 X5.0891 Y9.4785 I0.0066 J-0.1123 -G1 X5.2548 Y9.4785 -G1 X5.306 Y9.636 -G2 X5.5205 Y9.6345 I0.107 J-0.0347 -G1 X5.5687 Y9.4785 -G1 X5.7369 Y9.4785 -G2 X5.7435 Y9.4783 I0 J-0.1125 -G2 X5.7331 Y9.5254 I0.1021 J0.0471 -G2 X5.7386 Y9.5602 I0.1125 J0 -G1 X5.7899 Y9.7177 -G1 X5.6559 Y9.8151 -G2 X5.6095 Y9.9061 I0.0661 J0.091 -G0 Z0.25 -G0 X7.4779 Y9.2651 -G1 Z-0.05 F30 -G2 X7.5567 Y9.1556 I-0.1664 J-0.203 F10 -G1 X7.5567 Y9.2668 -G2 X7.4779 Y9.2651 I-0.0451 J0.2586 -G0 Z0.25 -G0 X7.2787 Y9.3225 -G1 Z-0.05 F30 -G2 X7.3443 Y9.3225 I0.0328 J-0.2604 F10 -G1 X7.3115 Y9.3464 -G1 X7.2787 Y9.3225 -G0 Z0.25 -G0 X7.2362 Y9.3535 -G1 Z-0.05 F30 -G2 X7.2132 Y9.3389 I-0.1249 J0.1719 F10 -G2 X7.1273 Y9.194 I-0.2108 J0.027 -G1 X7.0521 Y9.1394 -G1 X7.0809 Y9.051 -G2 X7.0826 Y9.0455 I-0.2021 J-0.0657 -G1 X7.1094 Y9.1278 -G2 X7.5145 Y9.1248 I0.2021 J-0.0657 -G1 X7.5409 Y9.0393 -G1 X7.6067 Y9.0393 -G1 X7.6067 Y9.3354 -G2 X7.3867 Y9.3535 I-0.0951 J0.19 -G1 X7.3115 Y9.4082 -G1 X7.2362 Y9.3535 -G1 X7.2068 Y9.3939 F10 -G2 X7.1648 Y9.372 I-0.0955 J0.1315 F10 -G2 X7.1649 Y9.366 I-0.1624 J-0.006 -G2 X7.0979 Y9.2345 I-0.1625 J0 -G1 X6.9934 Y9.1585 -G1 X7.0334 Y9.0355 -G2 X7.0413 Y8.9893 I-0.1545 J-0.0503 -G1 X7.1169 Y8.9893 -G1 X7.1569 Y9.1123 -G2 X7.4667 Y9.11 I0.1545 J-0.0503 -G1 X7.504 Y8.9893 -G1 X7.6352 Y8.9893 -G2 X7.6567 Y8.9879 I0 J-0.1625 -G1 X7.6567 Y9.4523 -G2 X7.4161 Y9.3939 I-0.1451 J0.0731 -G1 X7.3115 Y9.47 -G1 X7.2068 Y9.3939 -G0 Z0.25 -G0 X7.6567 Y9.6045 -G1 Z-0.05 F30 -G1 X7.6567 Y9.7209 F10 -G1 X7.6261 Y9.6986 -G1 X7.6567 Y9.6045 -G0 Z0.25 -G0 X7.6186 Y9.5602 -G1 Z-0.05 F30 -G2 X7.6241 Y9.5254 I-0.107 J-0.0348 F10 -G2 X7.4455 Y9.4344 I-0.1125 J0 -G1 X7.3115 Y9.5318 -G1 X7.1774 Y9.4344 -G2 X7.1046 Y9.4131 I-0.0661 J0.091 -G2 X7.1149 Y9.366 I-0.1021 J-0.0471 -G2 X7.0686 Y9.2749 I-0.1125 J0 -G1 X6.9346 Y9.1776 -G1 X6.9858 Y9.0201 -G2 X6.9913 Y8.9853 I-0.107 J-0.0348 -G2 X6.9814 Y8.9391 I-0.1125 J0 -G2 X6.9876 Y8.9393 I0.0061 J-0.1123 -G1 X7.1532 Y8.9393 -G1 X7.2045 Y9.0969 -G2 X7.419 Y9.0953 I0.107 J-0.0348 -G1 X7.4671 Y8.9393 -G1 X7.6352 Y8.9393 -G2 X7.7067 Y8.9136 I0 J-0.1125 -G1 X7.7067 Y9.8193 -G2 X7.7013 Y9.8151 I-0.0715 J0.0868 -G1 X7.5673 Y9.7177 -G1 X7.6186 Y9.5602 -G0 Z0.25 -G0 X7.4779 Y7.1088 -G1 Z-0.05 F30 -G2 X7.5567 Y6.9993 I-0.1664 J-0.203 F10 -G1 X7.5567 Y7.1106 -G2 X7.4779 Y7.1088 I-0.0451 J0.2586 -G0 Z0.25 -G0 X7.2787 Y7.1663 -G1 Z-0.05 F30 -G2 X7.3443 Y7.1663 I0.0328 J-0.2604 F10 -G1 X7.3115 Y7.1901 -G1 X7.2787 Y7.1663 -G0 Z0.25 -G0 X7.2362 Y7.1972 -G1 Z-0.05 F30 -G2 X7.2132 Y7.1827 I-0.1249 J0.1719 F10 -G2 X7.1273 Y7.0378 I-0.2108 J0.027 -G1 X7.0521 Y6.9832 -G1 X7.0809 Y6.8947 -G2 X7.0826 Y6.8892 I-0.2021 J-0.0657 -G1 X7.1094 Y6.9716 -G2 X7.5145 Y6.9685 I0.2021 J-0.0657 -G1 X7.5409 Y6.883 -G1 X7.6067 Y6.883 -G1 X7.6067 Y7.1791 -G2 X7.3867 Y7.1972 I-0.0951 J0.19 -G1 X7.3115 Y7.2519 -G1 X7.2362 Y7.1972 -G1 X7.2068 Y7.2377 F10 -G2 X7.1648 Y7.2157 I-0.0955 J0.1315 F10 -G2 X7.1649 Y7.2097 I-0.1624 J-0.006 -G2 X7.0979 Y7.0782 I-0.1625 J0 -G1 X6.9934 Y7.0023 -G1 X7.0334 Y6.8793 -G2 X7.0413 Y6.833 I-0.1545 J-0.0503 -G1 X7.1169 Y6.833 -G1 X7.1569 Y6.9561 -G2 X7.4667 Y6.9538 I0.1545 J-0.0503 -G1 X7.504 Y6.833 -G1 X7.6352 Y6.833 -G2 X7.6567 Y6.8316 I0 J-0.1625 -G1 X7.6567 Y7.2961 -G2 X7.4161 Y7.2377 I-0.1451 J0.0731 -G1 X7.3115 Y7.3137 -G1 X7.2068 Y7.2377 -G0 Z0.25 -G0 X7.6567 Y7.4483 -G1 Z-0.05 F30 -G1 X7.6567 Y7.5646 F10 -G1 X7.6261 Y7.5424 -G1 X7.6567 Y7.4483 -G0 Z0.25 -G0 X7.6186 Y7.404 -G1 Z-0.05 F30 -G2 X7.6241 Y7.3692 I-0.107 J-0.0348 F10 -G2 X7.4455 Y7.2781 I-0.1125 J0 -G1 X7.3115 Y7.3755 -G1 X7.1774 Y7.2781 -G2 X7.1046 Y7.2569 I-0.0661 J0.091 -G2 X7.1149 Y7.2097 I-0.1021 J-0.0471 -G2 X7.0686 Y7.1187 I-0.1125 J0 -G1 X6.9346 Y7.0213 -G1 X6.9858 Y6.8638 -G2 X6.9913 Y6.829 I-0.107 J-0.0348 -G2 X6.9814 Y6.7829 I-0.1125 J0 -G2 X6.9876 Y6.783 I0.0061 J-0.1123 -G1 X7.1532 Y6.783 -G1 X7.2045 Y6.9406 -G2 X7.419 Y6.939 I0.107 J-0.0348 -G1 X7.4671 Y6.783 -G1 X7.6352 Y6.783 -G2 X7.7067 Y6.7574 I0 J-0.1125 -G1 X7.7067 Y7.663 -G2 X7.7013 Y7.6588 I-0.0715 J0.0868 -G1 X7.5673 Y7.5615 -G1 X7.6186 Y7.404 -G0 Z0.25 -G0 X0.738 Y6.9993 -G1 Z-0.05 F30 -G2 X0.8168 Y7.1088 I0.2453 J-0.0935 F10 -G2 X0.738 Y7.1106 I-0.0337 J0.2603 -G1 X0.738 Y6.9993 -G0 Z0.25 -G0 X0.9505 Y7.1663 -G1 Z-0.05 F30 -G2 X1.0161 Y7.1663 I0.0328 J-0.2604 F10 -G1 X0.9833 Y7.1901 -G1 X0.9505 Y7.1663 -G0 Z0.25 -G0 X0.908 Y7.1972 -G1 Z-0.05 F30 -G2 X0.688 Y7.1791 I-0.1249 J0.1719 F10 -G1 X0.688 Y6.883 -G1 X0.7524 Y6.883 -G1 X0.7811 Y6.9714 -G2 X1.1863 Y6.9686 I0.2021 J-0.0656 -G1 X1.2115 Y6.8871 -G2 X1.2138 Y6.8947 I0.2044 J-0.0581 -G1 X1.2426 Y6.9832 -G1 X1.1674 Y7.0378 -G2 X1.0815 Y7.1827 I0.1249 J0.1719 -G2 X1.0585 Y7.1972 I0.1019 J0.1865 -G1 X0.9833 Y7.2519 -G1 X0.908 Y7.1972 -G1 X0.8786 Y7.2377 F10 -G2 X0.638 Y7.2961 I-0.0955 J0.1315 F10 -G1 X0.638 Y6.8316 -G2 X0.6595 Y6.833 I0.0215 J-0.1611 -G1 X0.7888 Y6.833 -G1 X0.8287 Y6.956 -G2 X1.1385 Y6.9538 I0.1546 J-0.0502 -G1 X1.1759 Y6.833 -G1 X1.2535 Y6.833 -G2 X1.2614 Y6.8793 I0.1625 J-0.004 -G1 X1.3014 Y7.0023 -G1 X1.1968 Y7.0782 -G2 X1.1298 Y7.2097 I0.0955 J0.1315 -G2 X1.1299 Y7.2157 I0.1625 J0 -G2 X1.0879 Y7.2377 I0.0535 J0.1534 -G1 X0.9833 Y7.3137 -G1 X0.8786 Y7.2377 -G0 Z0.25 -G0 X0.638 Y7.5646 -G1 Z-0.05 F30 -G1 X0.638 Y7.4483 F10 -G1 X0.6686 Y7.5424 -G1 X0.638 Y7.5646 -G0 Z0.25 -G0 X0.7274 Y7.5615 -G1 Z-0.05 F30 -G1 X0.5934 Y7.6588 F10 -G2 X0.588 Y7.663 I0.0661 J0.091 -G1 X0.588 Y6.7574 -G2 X0.6595 Y6.783 I0.0715 J-0.0868 -G1 X0.8251 Y6.783 -G1 X0.8763 Y6.9406 -G2 X1.0907 Y6.9391 I0.107 J-0.0347 -G1 X1.139 Y6.783 -G1 X1.3072 Y6.783 -G2 X1.3133 Y6.7829 I0 J-0.1125 -G2 X1.3034 Y6.829 I0.1026 J0.0461 -G2 X1.3089 Y6.8638 I0.1125 J0 -G1 X1.3602 Y7.0213 -G1 X1.2262 Y7.1187 -G2 X1.1798 Y7.2097 I0.0661 J0.091 -G2 X1.1901 Y7.2569 I0.1125 J0 -G2 X1.1173 Y7.2781 I-0.0067 J0.1123 -G1 X0.9833 Y7.3755 -G1 X0.8493 Y7.2781 -G2 X0.6706 Y7.3692 I-0.0661 J0.091 -G2 X0.6761 Y7.404 I0.1125 J0 -G1 X0.7274 Y7.5615 -G0 Z0.25 -G0 X0.738 Y9.1556 -G1 Z-0.05 F30 -G2 X0.8168 Y9.2651 I0.2453 J-0.0935 F10 -G2 X0.738 Y9.2668 I-0.0337 J0.2603 -G1 X0.738 Y9.1556 -G0 Z0.25 -G0 X0.9505 Y9.3225 -G1 Z-0.05 F30 -G2 X1.0161 Y9.3225 I0.0328 J-0.2604 F10 -G1 X0.9833 Y9.3464 -G1 X0.9505 Y9.3225 -G0 Z0.25 -G0 X0.908 Y9.3535 -G1 Z-0.05 F30 -G2 X0.688 Y9.3354 I-0.1249 J0.1719 F10 -G1 X0.688 Y9.0393 -G1 X0.7524 Y9.0393 -G1 X0.7811 Y9.1277 -G2 X1.1863 Y9.1249 I0.2021 J-0.0656 -G1 X1.2115 Y9.0433 -G2 X1.2138 Y9.051 I0.2044 J-0.0581 -G1 X1.2426 Y9.1394 -G1 X1.1674 Y9.194 -G2 X1.0815 Y9.3389 I0.1249 J0.1719 -G2 X1.0585 Y9.3535 I0.1019 J0.1865 -G1 X0.9833 Y9.4082 -G1 X0.908 Y9.3535 -G1 X0.8786 Y9.3939 F10 -G2 X0.638 Y9.4523 I-0.0955 J0.1315 F10 -G1 X0.638 Y8.9879 -G2 X0.6595 Y8.9893 I0.0215 J-0.1611 -G1 X0.7888 Y8.9893 -G1 X0.8287 Y9.1123 -G2 X1.1385 Y9.1101 I0.1546 J-0.0502 -G1 X1.1759 Y8.9893 -G1 X1.2535 Y8.9893 -G2 X1.2614 Y9.0355 I0.1625 J-0.004 -G1 X1.3014 Y9.1585 -G1 X1.1968 Y9.2345 -G2 X1.1298 Y9.366 I0.0955 J0.1315 -G2 X1.1299 Y9.372 I0.1625 J0 -G2 X1.0879 Y9.3939 I0.0535 J0.1534 -G1 X0.9833 Y9.47 -G1 X0.8786 Y9.3939 -G0 Z0.25 -G0 X0.638 Y9.7209 -G1 Z-0.05 F30 -G1 X0.638 Y9.6045 F10 -G1 X0.6686 Y9.6986 -G1 X0.638 Y9.7209 -G0 Z0.25 -G0 X0.7274 Y9.7177 -G1 Z-0.05 F30 -G1 X0.5934 Y9.8151 F10 -G2 X0.588 Y9.8193 I0.0661 J0.091 -G1 X0.588 Y8.9136 -G2 X0.6595 Y8.9393 I0.0715 J-0.0868 -G1 X0.8251 Y8.9393 -G1 X0.8763 Y9.0968 -G2 X1.0907 Y9.0953 I0.107 J-0.0347 -G1 X1.139 Y8.9393 -G1 X1.3072 Y8.9393 -G2 X1.3133 Y8.9391 I0 J-0.1125 -G2 X1.3034 Y8.9853 I0.1026 J0.0461 -G2 X1.3089 Y9.0201 I0.1125 J0 -G1 X1.3602 Y9.1776 -G1 X1.2262 Y9.2749 -G2 X1.1798 Y9.366 I0.0661 J0.091 -G2 X1.1901 Y9.4131 I0.1125 J0 -G2 X1.1173 Y9.4344 I-0.0067 J0.1123 -G1 X0.9833 Y9.5318 -G1 X0.8493 Y9.4344 -G2 X0.6706 Y9.5254 I-0.0661 J0.091 -G2 X0.6761 Y9.5602 I0.1125 J0 -G1 X0.7274 Y9.7177 -G0 Z0.25 -G0 X7.4797 Y6.0293 -G1 Z-0.05 F30 -G2 X7.5567 Y5.9213 I-0.1682 J-0.2015 F10 -G1 X7.5567 Y6.0313 -G2 X7.4797 Y6.0293 I-0.0451 J0.2586 -G0 Z0.25 -G0 X7.2807 Y6.0885 -G1 Z-0.05 F30 -G2 X7.3422 Y6.0885 I0.0307 J-0.2607 F10 -G1 X7.3115 Y6.1108 -G1 X7.2807 Y6.0885 -G0 Z0.25 -G0 X7.2362 Y6.1179 -G1 Z-0.05 F30 -G2 X7.213 Y6.1033 I-0.1249 J0.1719 F10 -G2 X7.1273 Y5.9596 I-0.2106 J0.0282 -G1 X7.0521 Y5.905 -G1 X7.0809 Y5.8166 -G2 X7.0826 Y5.8111 I-0.2021 J-0.0657 -G1 X7.1094 Y5.8935 -G2 X7.5145 Y5.8905 I0.2021 J-0.0657 -G1 X7.5409 Y5.805 -G1 X7.6067 Y5.805 -G1 X7.6067 Y6.0998 -G2 X7.3867 Y6.1179 I-0.0951 J0.19 -G1 X7.3115 Y6.1726 -G1 X7.2362 Y6.1179 -G1 X7.2068 Y6.1584 F10 -G2 X7.1649 Y6.1364 I-0.0955 J0.1315 F10 -G2 X7.1649 Y6.1315 I-0.1624 J-0.0049 -G2 X7.0979 Y6.0001 I-0.1625 J0 -G1 X6.9934 Y5.9241 -G1 X7.0334 Y5.8011 -G2 X7.0413 Y5.755 I-0.1545 J-0.0503 -G1 X7.1169 Y5.755 -G1 X7.1569 Y5.878 -G2 X7.4667 Y5.8757 I0.1545 J-0.0503 -G1 X7.504 Y5.755 -G1 X7.6352 Y5.755 -G2 X7.6567 Y5.7536 I0 J-0.1625 -G1 X7.6567 Y6.2168 -G2 X7.4161 Y6.1584 I-0.1451 J0.0731 -G1 X7.3115 Y6.2344 -G1 X7.2068 Y6.1584 -G0 Z0.25 -G0 X7.6567 Y6.369 -G1 Z-0.05 F30 -G1 X7.6567 Y6.4853 F10 -G1 X7.6261 Y6.4631 -G1 X7.6567 Y6.369 -G0 Z0.25 -G0 X7.6186 Y6.3246 -G1 Z-0.05 F30 -G2 X7.6241 Y6.2899 I-0.107 J-0.0348 F10 -G2 X7.4455 Y6.1988 I-0.1125 J0 -G1 X7.3115 Y6.2962 -G1 X7.1774 Y6.1988 -G2 X7.1051 Y6.1775 I-0.0661 J0.091 -G2 X7.1149 Y6.1315 I-0.1027 J-0.046 -G2 X7.0686 Y6.0405 I-0.1125 J0 -G1 X6.9346 Y5.9431 -G1 X6.9858 Y5.7856 -G2 X6.9913 Y5.7508 I-0.107 J-0.0348 -G2 X6.9815 Y5.7048 I-0.1125 J0 -G2 X6.9876 Y5.705 I0.0061 J-0.1123 -G1 X7.1532 Y5.705 -G1 X7.2045 Y5.8626 -G2 X7.419 Y5.861 I0.107 J-0.0348 -G1 X7.4671 Y5.705 -G1 X7.6352 Y5.705 -G2 X7.7067 Y5.6793 I0 J-0.1125 -G1 X7.7067 Y6.5837 -G2 X7.7013 Y6.5795 I-0.0715 J0.0868 -G1 X7.5673 Y6.4822 -G1 X7.6186 Y6.3246 -G0 Z0.25 -G0 X0.738 Y5.9213 -G1 Z-0.05 F30 -G2 X0.8151 Y6.0293 I0.2453 J-0.0935 F10 -G2 X0.738 Y6.0313 I-0.0319 J0.2605 -G1 X0.738 Y5.9213 -G0 Z0.25 -G0 X0.9525 Y6.0885 -G1 Z-0.05 F30 -G2 X1.014 Y6.0885 I0.0307 J-0.2607 F10 -G1 X0.9833 Y6.1108 -G1 X0.9525 Y6.0885 -G0 Z0.25 -G0 X0.908 Y6.1179 -G1 Z-0.05 F30 -G2 X0.688 Y6.0998 I-0.1249 J0.1719 F10 -G1 X0.688 Y5.805 -G1 X0.7524 Y5.805 -G1 X0.7811 Y5.8934 -G2 X1.1863 Y5.8906 I0.2021 J-0.0656 -G1 X1.2115 Y5.809 -G2 X1.2138 Y5.8166 I0.2044 J-0.0581 -G1 X1.2426 Y5.905 -G1 X1.1674 Y5.9596 -G2 X1.0817 Y6.1033 I0.1249 J0.1719 -G2 X1.0585 Y6.1179 I0.1017 J0.1866 -G1 X0.9833 Y6.1726 -G1 X0.908 Y6.1179 -G1 X0.8786 Y6.1584 F10 -G2 X0.638 Y6.2168 I-0.0955 J0.1315 F10 -G1 X0.638 Y5.7536 -G2 X0.6595 Y5.755 I0.0215 J-0.1611 -G1 X0.7888 Y5.755 -G1 X0.8287 Y5.8779 -G2 X1.1385 Y5.8758 I0.1546 J-0.0502 -G1 X1.1759 Y5.755 -G1 X1.2535 Y5.755 -G2 X1.2614 Y5.8011 I0.1624 J-0.0042 -G1 X1.3014 Y5.9241 -G1 X1.1968 Y6.0001 -G2 X1.1298 Y6.1315 I0.0955 J0.1315 -G2 X1.1299 Y6.1364 I0.1625 J0 -G2 X1.0879 Y6.1584 I0.0535 J0.1534 -G1 X0.9833 Y6.2344 -G1 X0.8786 Y6.1584 -G0 Z0.25 -G0 X0.638 Y6.4853 -G1 Z-0.05 F30 -G1 X0.638 Y6.369 F10 -G1 X0.6686 Y6.4631 -G1 X0.638 Y6.4853 -G0 Z0.25 -G0 X0.7274 Y6.4822 -G1 Z-0.05 F30 -G1 X0.5934 Y6.5795 F10 -G2 X0.588 Y6.5837 I0.0661 J0.091 -G1 X0.588 Y5.6793 -G2 X0.6595 Y5.705 I0.0715 J-0.0868 -G1 X0.8251 Y5.705 -G1 X0.8763 Y5.8625 -G2 X1.0907 Y5.861 I0.107 J-0.0347 -G1 X1.139 Y5.705 -G1 X1.3072 Y5.705 -G2 X1.3132 Y5.7048 I0 J-0.1125 -G2 X1.3034 Y5.7508 I0.1027 J0.046 -G2 X1.3089 Y5.7856 I0.1125 J0 -G1 X1.3602 Y5.9431 -G1 X1.2262 Y6.0405 -G2 X1.1798 Y6.1315 I0.0661 J0.091 -G2 X1.1896 Y6.1775 I0.1125 J0 -G2 X1.1173 Y6.1988 I-0.0062 J0.1123 -G1 X0.9833 Y6.2962 -G1 X0.8493 Y6.1988 -G2 X0.6706 Y6.2899 I-0.0661 J0.091 -G2 X0.6761 Y6.3246 I0.1125 J0 -G1 X0.7274 Y6.4822 -G0 Z0.25 -G0 X7.4814 Y8.1853 -G1 Z-0.05 F30 -G2 X7.5567 Y8.0788 I-0.1699 J-0.2001 F10 -G1 X7.5567 Y8.1875 -G2 X7.4814 Y8.1853 I-0.0451 J0.2586 -G0 Z0.25 -G0 X7.2828 Y8.2462 -G1 Z-0.05 F30 -G2 X7.3402 Y8.2462 I0.0287 J-0.2609 F10 -G1 X7.3115 Y8.267 -G1 X7.2828 Y8.2462 -G0 Z0.25 -G0 X7.2362 Y8.2742 -G1 Z-0.05 F30 -G2 X7.213 Y8.2595 I-0.1249 J0.1719 F10 -G2 X7.1273 Y8.1159 I-0.2106 J0.0282 -G1 X7.0521 Y8.0612 -G1 X7.0809 Y7.9728 -G2 X7.0824 Y7.968 I-0.2021 J-0.0657 -G1 X7.1094 Y8.051 -G2 X7.5145 Y8.0479 I0.2021 J-0.0657 -G1 X7.5409 Y7.9624 -G1 X7.6067 Y7.9624 -G1 X7.6067 Y8.2561 -G2 X7.3867 Y8.2742 I-0.0951 J0.19 -G1 X7.3115 Y8.3288 -G1 X7.2362 Y8.2742 -G1 X7.2068 Y8.3146 F10 -G2 X7.1649 Y8.2927 I-0.0955 J0.1315 F10 -G2 X7.1649 Y8.2878 I-0.1624 J-0.0049 -G2 X7.0979 Y8.1563 I-0.1625 J0 -G1 X6.9934 Y8.0803 -G1 X7.0334 Y7.9573 -G2 X7.0412 Y7.9124 I-0.1545 J-0.0503 -G1 X7.1169 Y7.9124 -G1 X7.1569 Y8.0355 -G2 X7.4667 Y8.0332 I0.1545 J-0.0502 -G1 X7.504 Y7.9124 -G1 X7.6352 Y7.9124 -G2 X7.6567 Y7.9109 I0 J-0.1625 -G1 X7.6567 Y8.373 -G2 X7.4161 Y8.3146 I-0.1451 J0.0731 -G1 X7.3115 Y8.3907 -G1 X7.2068 Y8.3146 -G0 Z0.25 -G0 X7.6567 Y8.5252 -G1 Z-0.05 F30 -G1 X7.6567 Y8.6416 F10 -G1 X7.6261 Y8.6193 -G1 X7.6567 Y8.5252 -G0 Z0.25 -G0 X7.6186 Y8.4809 -G1 Z-0.05 F30 -G2 X7.6241 Y8.4461 I-0.107 J-0.0348 F10 -G2 X7.4455 Y8.3551 I-0.1125 J0 -G1 X7.3115 Y8.4525 -G1 X7.1774 Y8.3551 -G2 X7.1051 Y8.3338 I-0.0661 J0.091 -G2 X7.1149 Y8.2878 I-0.1027 J-0.046 -G2 X7.0686 Y8.1968 I-0.1125 J0 -G1 X6.9346 Y8.0994 -G1 X6.9858 Y7.9419 -G2 X6.9913 Y7.9071 I-0.107 J-0.0348 -G2 X6.982 Y7.8622 I-0.1125 J0 -G2 X6.9876 Y7.8624 I0.0056 J-0.1124 -G1 X7.1532 Y7.8624 -G1 X7.2045 Y8.02 -G2 X7.419 Y8.0184 I0.107 J-0.0348 -G1 X7.4671 Y7.8624 -G1 X7.6352 Y7.8624 -G2 X7.7067 Y7.8367 I0 J-0.1125 -G1 X7.7067 Y8.74 -G2 X7.7013 Y8.7358 I-0.0715 J0.0868 -G1 X7.5673 Y8.6384 -G1 X7.6186 Y8.4809 -G0 Z0.25 -G0 X0.738 Y8.0788 -G1 Z-0.05 F30 -G2 X0.8133 Y8.1853 I0.2453 J-0.0935 F10 -G2 X0.738 Y8.1875 I-0.0302 J0.2608 -G1 X0.738 Y8.0788 -G0 Z0.25 -G0 X0.9546 Y8.2462 -G1 Z-0.05 F30 -G2 X1.012 Y8.2462 I0.0287 J-0.2609 F10 -G1 X0.9833 Y8.267 -G1 X0.9546 Y8.2462 -G0 Z0.25 -G0 X0.908 Y8.2742 -G1 Z-0.05 F30 -G2 X0.688 Y8.2561 I-0.1249 J0.1719 F10 -G1 X0.688 Y7.9624 -G1 X0.7524 Y7.9624 -G1 X0.7811 Y8.0509 -G2 X1.1863 Y8.048 I0.2021 J-0.0656 -G1 X1.2117 Y7.9658 -G2 X1.2138 Y7.9728 I0.2042 J-0.0588 -G1 X1.2426 Y8.0612 -G1 X1.1674 Y8.1159 -G2 X1.0817 Y8.2595 I0.1249 J0.1719 -G2 X1.0585 Y8.2742 I0.1017 J0.1866 -G1 X0.9833 Y8.3288 -G1 X0.908 Y8.2742 -G1 X0.8786 Y8.3146 F10 -G2 X0.638 Y8.373 I-0.0955 J0.1315 F10 -G1 X0.638 Y7.9109 -G2 X0.6595 Y7.9124 I0.0215 J-0.1611 -G1 X0.7888 Y7.9124 -G1 X0.8287 Y8.0354 -G2 X1.1385 Y8.0333 I0.1546 J-0.0502 -G1 X1.1759 Y7.9124 -G1 X1.2535 Y7.9124 -G2 X1.2614 Y7.9573 I0.1624 J-0.0053 -G1 X1.3014 Y8.0803 -G1 X1.1968 Y8.1563 -G2 X1.1298 Y8.2878 I0.0955 J0.1315 -G2 X1.1299 Y8.2927 I0.1625 J0 -G2 X1.0879 Y8.3146 I0.0535 J0.1534 -G1 X0.9833 Y8.3907 -G1 X0.8786 Y8.3146 -G0 Z0.25 -G0 X0.638 Y8.6416 -G1 Z-0.05 F30 -G1 X0.638 Y8.5252 F10 -G1 X0.6686 Y8.6193 -G1 X0.638 Y8.6416 -G0 Z0.25 -G0 X0.7274 Y8.6384 -G1 Z-0.05 F30 -G1 X0.5934 Y8.7358 F10 -G2 X0.588 Y8.74 I0.0661 J0.091 -G1 X0.588 Y7.8367 -G2 X0.6595 Y7.8624 I0.0715 J-0.0868 -G1 X0.8251 Y7.8624 -G1 X0.8763 Y8.02 -G2 X1.0907 Y8.0185 I0.107 J-0.0347 -G1 X1.139 Y7.8624 -G1 X1.3072 Y7.8624 -G2 X1.3127 Y7.8622 I0 J-0.1125 -G2 X1.3034 Y7.9071 I0.1032 J0.0449 -G2 X1.3089 Y7.9419 I0.1125 J0 -G1 X1.3602 Y8.0994 -G1 X1.2262 Y8.1968 -G2 X1.1798 Y8.2878 I0.0661 J0.091 -G2 X1.1896 Y8.3338 I0.1125 J0 -G2 X1.1173 Y8.3551 I-0.0062 J0.1123 -G1 X0.9833 Y8.4525 -G1 X0.8493 Y8.3551 -G2 X0.6706 Y8.4461 I-0.0661 J0.091 -G2 X0.6761 Y8.4809 I0.1125 J0 -G1 X0.7274 Y8.6384 -G0 Z0.25 -G0 X1.579 Y5.4383 -G1 Z-0.05 F30 -G1 X1.6532 Y5.4383 F10 -G2 X1.6256 Y5.5031 I0.2718 J0.1542 -G1 X1.6161 Y5.51 -G1 X1.6066 Y5.5031 -G2 X1.579 Y5.4383 I-0.2994 J0.0894 -G1 X1.5629 Y5.5333 F10 -G2 X1.4721 Y5.3883 I-0.2557 J0.0591 F10 -G1 X1.7601 Y5.3883 -G2 X1.6693 Y5.5333 I0.165 J0.2042 -G2 X1.662 Y5.5385 I0.147 J0.2175 -G1 X1.6161 Y5.5718 -G1 X1.5701 Y5.5384 -G2 X1.5629 Y5.5333 I-0.1542 J0.2124 -G1 X1.5408 Y5.5789 F10 -G2 X1.5178 Y5.5643 I-0.1249 J0.172 F10 -G2 X1.4321 Y5.4206 I-0.2106 J0.0282 -G1 X1.3568 Y5.3659 -G1 X1.3657 Y5.3383 -G1 X1.8665 Y5.3383 -G1 X1.8754 Y5.3659 -G1 X1.8002 Y5.4206 -G2 X1.7144 Y5.5643 I0.1249 J0.1719 -G2 X1.6914 Y5.5789 I0.1019 J0.1865 -G1 X1.6161 Y5.6336 -G1 X1.5408 Y5.5789 -G1 X1.5114 Y5.6193 F10 -G2 X1.4696 Y5.5974 I-0.0955 J0.1315 F10 -G2 X1.4697 Y5.5925 I-0.1624 J-0.005 -G2 X1.4027 Y5.461 I-0.1625 J0 -G1 X1.298 Y5.385 -G1 X1.3294 Y5.2883 -G1 X1.9028 Y5.2883 -G1 X1.9342 Y5.385 -G1 X1.8296 Y5.461 -G2 X1.7626 Y5.5925 I0.0955 J0.1315 -G2 X1.7626 Y5.5974 I0.1625 J0 -G2 X1.7208 Y5.6194 I0.0537 J0.1534 -G1 X1.6161 Y5.6954 -G1 X1.5114 Y5.6193 -G1 X1.482 Y5.6598 F10 -G2 X1.4098 Y5.6385 I-0.0661 J0.091 F10 -G2 X1.4197 Y5.5925 I-0.1027 J-0.046 -G2 X1.3733 Y5.5015 I-0.1125 J0 -G1 X1.2392 Y5.4041 -G1 X1.2904 Y5.2465 -G2 X1.2927 Y5.2383 I-0.107 J-0.0347 -G1 X1.9395 Y5.2383 -G2 X1.9418 Y5.2465 I0.1093 J-0.0265 -G1 X1.993 Y5.4041 -G1 X1.8589 Y5.5015 -G2 X1.8126 Y5.5925 I0.0661 J0.091 -G2 X1.8224 Y5.6385 I0.1125 J0 -G2 X1.7502 Y5.6598 I-0.0061 J0.1123 -G1 X1.6162 Y5.7572 -G1 X1.482 Y5.6598 -G0 Z0.25 -G0 X4.1102 Y5.4383 -G1 Z-0.05 F30 -G1 X4.1845 Y5.4383 F10 -G2 X4.1569 Y5.5031 I0.2718 J0.1542 -G1 X4.1474 Y5.51 -G1 X4.1378 Y5.5031 -G2 X4.1102 Y5.4383 I-0.2994 J0.0894 -G1 X4.0942 Y5.5333 F10 -G2 X4.0034 Y5.3883 I-0.2557 J0.0591 F10 -G1 X4.2913 Y5.3883 -G2 X4.2006 Y5.5333 I0.165 J0.2042 -G2 X4.1933 Y5.5384 I0.147 J0.2175 -G1 X4.1473 Y5.5718 -G1 X4.1015 Y5.5385 -G2 X4.0942 Y5.5333 I-0.1543 J0.2124 -G1 X4.0721 Y5.5789 F10 -G2 X4.049 Y5.5643 I-0.1249 J0.1719 F10 -G2 X3.9633 Y5.4206 I-0.2106 J0.0282 -G1 X3.888 Y5.3659 -G1 X3.897 Y5.3383 -G1 X4.3977 Y5.3383 -G1 X4.4067 Y5.3659 -G1 X4.3314 Y5.4206 -G2 X4.2457 Y5.5643 I0.1249 J0.1719 -G2 X4.2227 Y5.5789 I0.1019 J0.1865 -G1 X4.1473 Y5.6336 -G1 X4.0721 Y5.5789 -G1 X4.0427 Y5.6194 F10 -G2 X4.0008 Y5.5974 I-0.0955 J0.1315 F10 -G2 X4.0009 Y5.5925 I-0.1624 J-0.005 -G2 X3.9339 Y5.461 I-0.1625 J0 -G1 X3.8293 Y5.385 -G1 X3.8607 Y5.2883 -G1 X4.4341 Y5.2883 -G1 X4.4655 Y5.385 -G1 X4.3608 Y5.461 -G2 X4.2938 Y5.5925 I0.0955 J0.1315 -G2 X4.2939 Y5.5974 I0.1625 J0 -G2 X4.2521 Y5.6193 I0.0537 J0.1534 -G1 X4.1473 Y5.6954 -G1 X4.0427 Y5.6194 -G1 X4.0133 Y5.6598 F10 -G2 X3.9411 Y5.6385 I-0.0661 J0.091 F10 -G2 X3.9509 Y5.5925 I-0.1027 J-0.046 -G2 X3.9045 Y5.5015 I-0.1125 J0 -G1 X3.7705 Y5.4041 -G1 X3.8217 Y5.2465 -G2 X3.824 Y5.2383 I-0.107 J-0.0347 -G1 X4.4707 Y5.2383 -G2 X4.4731 Y5.2465 I0.1093 J-0.0265 -G1 X4.5242 Y5.4041 -G1 X4.3902 Y5.5015 -G2 X4.3438 Y5.5925 I0.0661 J0.091 -G2 X4.3537 Y5.6385 I0.1125 J0 -G2 X4.2815 Y5.6598 I-0.0061 J0.1123 -G1 X4.1473 Y5.7572 -G1 X4.0133 Y5.6598 -G0 Z0.25 -G0 X6.6415 Y5.4383 -G1 Z-0.05 F30 -G1 X6.7157 Y5.4383 F10 -G2 X6.6881 Y5.5031 I0.2718 J0.1542 -G1 X6.6786 Y5.51 -G1 X6.6691 Y5.5031 -G2 X6.6415 Y5.4383 I-0.2994 J0.0894 -G1 X6.6254 Y5.5333 F10 -G2 X6.5346 Y5.3883 I-0.2557 J0.0591 F10 -G1 X6.8226 Y5.3883 -G2 X6.7318 Y5.5333 I0.165 J0.2042 -G2 X6.7246 Y5.5384 I0.147 J0.2175 -G1 X6.6786 Y5.5718 -G1 X6.6327 Y5.5385 -G2 X6.6254 Y5.5333 I-0.1543 J0.2124 -G1 X6.6033 Y5.5789 F10 -G2 X6.5803 Y5.5643 I-0.1249 J0.1719 F10 -G2 X6.4946 Y5.4206 I-0.2106 J0.0282 -G1 X6.4193 Y5.3659 -G1 X6.4282 Y5.3383 -G1 X6.929 Y5.3383 -G1 X6.9379 Y5.3659 -G1 X6.8627 Y5.4206 -G2 X6.7769 Y5.5643 I0.1249 J0.1719 -G2 X6.754 Y5.5789 I0.1019 J0.1865 -G1 X6.6786 Y5.6336 -G1 X6.6033 Y5.5789 -G1 X6.5739 Y5.6194 F10 -G2 X6.5321 Y5.5974 I-0.0955 J0.1315 F10 -G2 X6.5322 Y5.5925 I-0.1624 J-0.005 -G2 X6.4652 Y5.461 I-0.1625 J0 -G1 X6.3605 Y5.385 -G1 X6.3919 Y5.2883 -G1 X6.9653 Y5.2883 -G1 X6.9967 Y5.385 -G1 X6.8921 Y5.461 -G2 X6.8251 Y5.5925 I0.0955 J0.1315 -G2 X6.8251 Y5.5974 I0.1625 J0 -G2 X6.7833 Y5.6193 I0.0537 J0.1534 -G1 X6.6786 Y5.6954 -G1 X6.5739 Y5.6194 -G1 X6.5445 Y5.6598 F10 -G2 X6.4723 Y5.6385 I-0.0661 J0.091 F10 -G2 X6.4822 Y5.5925 I-0.1027 J-0.046 -G2 X6.4358 Y5.5015 I-0.1125 J0 -G1 X6.3017 Y5.4041 -G1 X6.3529 Y5.2465 -G2 X6.3552 Y5.2383 I-0.107 J-0.0347 -G1 X7.002 Y5.2383 -G2 X7.0043 Y5.2465 I0.1093 J-0.0265 -G1 X7.0555 Y5.4041 -G1 X6.9214 Y5.5015 -G2 X6.8751 Y5.5925 I0.0661 J0.091 -G2 X6.8849 Y5.6385 I0.1125 J0 -G2 X6.8127 Y5.6598 I-0.0061 J0.1123 -G1 X6.6786 Y5.7572 -G1 X6.5445 Y5.6598 -G0 Z0.25 -G0 X2.8445 Y5.4383 -G1 Z-0.05 F30 -G1 X2.9189 Y5.4383 F10 -G2 X2.8914 Y5.503 I0.2718 J0.1542 -G1 X2.8817 Y5.51 -G1 X2.8721 Y5.503 -G2 X2.8445 Y5.4383 I-0.2994 J0.0895 -G1 X2.8284 Y5.5332 F10 -G2 X2.7377 Y5.3883 I-0.2557 J0.0593 F10 -G1 X3.0258 Y5.3883 -G2 X2.935 Y5.5332 I0.165 J0.2042 -G2 X2.9276 Y5.5385 I0.1468 J0.2176 -G1 X2.8817 Y5.5718 -G1 X2.8359 Y5.5385 -G2 X2.8284 Y5.5332 I-0.1543 J0.2124 -G1 X2.8065 Y5.5789 F10 -G2 X2.7833 Y5.5643 I-0.1249 J0.1719 F10 -G2 X2.6976 Y5.4206 I-0.2106 J0.0282 -G1 X2.6224 Y5.3659 -G1 X2.6314 Y5.3383 -G1 X3.1321 Y5.3383 -G1 X3.1411 Y5.3659 -G1 X3.0659 Y5.4206 -G2 X2.9801 Y5.5643 I0.1249 J0.1719 -G2 X2.957 Y5.5789 I0.1017 J0.1866 -G1 X2.8817 Y5.6336 -G1 X2.8065 Y5.5789 -G1 X2.7771 Y5.6194 F10 -G2 X2.7351 Y5.5974 I-0.0955 J0.1315 F10 -G2 X2.7352 Y5.5925 I-0.1624 J-0.0049 -G2 X2.6682 Y5.461 I-0.1625 J0 -G1 X2.5636 Y5.385 -G1 X2.5951 Y5.2883 -G1 X3.1684 Y5.2883 -G1 X3.1998 Y5.385 -G1 X3.0952 Y5.461 -G2 X3.0283 Y5.5925 I0.0955 J0.1315 -G2 X3.0283 Y5.5974 I0.1625 J0 -G2 X2.9864 Y5.6194 I0.0535 J0.1534 -G1 X2.8817 Y5.6954 -G1 X2.7771 Y5.6194 -G1 X2.7477 Y5.6598 F10 -G2 X2.6754 Y5.6385 I-0.0661 J0.091 F10 -G2 X2.6852 Y5.5925 I-0.1027 J-0.046 -G2 X2.6388 Y5.5015 I-0.1125 J0 -G1 X2.5048 Y5.4041 -G1 X2.5561 Y5.2466 -G2 X2.5584 Y5.2383 I-0.107 J-0.0348 -G1 X3.205 Y5.2383 -G2 X3.2074 Y5.2466 I0.1093 J-0.0265 -G1 X3.2586 Y5.4041 -G1 X3.1246 Y5.5015 -G2 X3.0783 Y5.5925 I0.0661 J0.091 -G2 X3.0881 Y5.6385 I0.1125 J0 -G2 X3.0157 Y5.6598 I-0.0062 J0.1123 -G1 X2.8817 Y5.7572 -G1 X2.7477 Y5.6598 -G0 Z0.25 -G0 X5.3758 Y5.4383 -G1 Z-0.05 F30 -G1 X5.4502 Y5.4383 F10 -G2 X5.4226 Y5.503 I0.2718 J0.1542 -G1 X5.413 Y5.51 -G1 X5.4034 Y5.503 -G2 X5.3758 Y5.4383 I-0.2994 J0.0895 -G1 X5.3597 Y5.5332 F10 -G2 X5.2689 Y5.3883 I-0.2557 J0.0593 F10 -G1 X5.557 Y5.3883 -G2 X5.4663 Y5.5332 I0.165 J0.2042 -G2 X5.4588 Y5.5385 I0.1468 J0.2176 -G1 X5.413 Y5.5718 -G1 X5.3671 Y5.5385 -G2 X5.3597 Y5.5332 I-0.1543 J0.2124 -G1 X5.3378 Y5.5789 F10 -G2 X5.3146 Y5.5643 I-0.1249 J0.1719 F10 -G2 X5.2289 Y5.4206 I-0.2106 J0.0282 -G1 X5.1537 Y5.3659 -G1 X5.1627 Y5.3383 -G1 X5.6633 Y5.3383 -G1 X5.6723 Y5.3659 -G1 X5.5971 Y5.4206 -G2 X5.5114 Y5.5643 I0.1249 J0.1719 -G2 X5.4882 Y5.5789 I0.1017 J0.1866 -G1 X5.413 Y5.6336 -G1 X5.3378 Y5.5789 -G1 X5.3084 Y5.6194 F10 -G2 X5.2664 Y5.5974 I-0.0955 J0.1315 F10 -G2 X5.2665 Y5.5925 I-0.1624 J-0.0049 -G2 X5.1995 Y5.461 I-0.1625 J0 -G1 X5.0949 Y5.385 -G1 X5.1263 Y5.2883 -G1 X5.6996 Y5.2883 -G1 X5.7311 Y5.385 -G1 X5.6265 Y5.461 -G2 X5.5595 Y5.5925 I0.0955 J0.1315 -G2 X5.5596 Y5.5974 I0.1625 J0 -G2 X5.5176 Y5.6194 I0.0535 J0.1534 -G1 X5.413 Y5.6954 -G1 X5.3084 Y5.6194 -G1 X5.279 Y5.6598 F10 -G2 X5.2066 Y5.6385 I-0.0661 J0.091 F10 -G2 X5.2165 Y5.5925 I-0.1027 J-0.046 -G2 X5.1701 Y5.5015 I-0.1125 J0 -G1 X5.0361 Y5.4041 -G1 X5.0873 Y5.2466 -G2 X5.0897 Y5.2383 I-0.107 J-0.0348 -G1 X5.7363 Y5.2383 -G2 X5.7386 Y5.2466 I0.1093 J-0.0265 -G1 X5.7899 Y5.4041 -G1 X5.6559 Y5.5015 -G2 X5.6095 Y5.5925 I0.0661 J0.091 -G2 X5.6194 Y5.6385 I0.1125 J0 -G2 X5.547 Y5.6598 I-0.0062 J0.1123 -G1 X5.413 Y5.7572 -G1 X5.279 Y5.6598 -G0 Z0.25 -G0 X7.6567 Y10.0883 -G1 Z-0.05 F30 -G1 X7.4979 Y10.0883 F10 -G1 X7.504 Y10.0686 -G1 X7.6352 Y10.0686 -G2 X7.6567 Y10.0672 I0 J-0.1625 -G1 X7.6567 Y10.0883 -G1 X7.7067 Y10.1383 F10 -G1 X7.4302 Y10.1383 F10 -G1 X7.4671 Y10.0186 -G1 X7.6352 Y10.0186 -G2 X7.7067 Y9.9929 I0 J-0.1125 -G1 X7.7067 Y10.1383 -G0 Z0.25 -G0 X0.7952 Y10.0883 -G1 Z-0.05 F30 -G1 X0.638 Y10.0883 F10 -G1 X0.638 Y10.0672 -G2 X0.6595 Y10.0686 I0.0215 J-0.1611 -G1 X0.7888 Y10.0686 -G1 X0.7952 Y10.0883 -G1 X0.8251 Y10.0186 F10 -G1 X0.864 Y10.1383 F10 -G1 X0.588 Y10.1383 -G1 X0.588 Y9.9929 -G2 X0.6595 Y10.0186 I0.0715 J-0.0868 -G1 X0.8251 Y10.0186 -G0 Z0.25 -G0 X7.6567 Y5.2909 -G1 Z-0.05 F30 -G1 X7.6567 Y5.4073 F10 -G1 X7.6261 Y5.385 -G1 X7.6567 Y5.2909 -G1 X7.6186 Y5.2466 F10 -G2 X7.6209 Y5.2383 I-0.107 J-0.0348 F10 -G1 X7.7067 Y5.2383 -G1 X7.7067 Y5.5057 -G2 X7.7013 Y5.5015 I-0.0715 J0.0868 -G1 X7.5673 Y5.4041 -G1 X7.6186 Y5.2466 -G0 Z0.25 -G0 X0.638 Y5.4073 -G1 Z-0.05 F30 -G1 X0.638 Y5.2909 F10 -G1 X0.6686 Y5.385 -G1 X0.638 Y5.4073 -G1 X0.7274 Y5.4041 F10 -G1 X0.5934 Y5.5015 F10 -G2 X0.588 Y5.5057 I0.0661 J0.091 -G1 X0.588 Y5.2383 -G1 X0.6738 Y5.2383 -G2 X0.6761 Y5.2466 I0.1093 J-0.0265 -G1 X0.7274 Y5.4041 -G0 Z0.25 -G0 X4.7515 Y8.2462 -G1 Z-0.05 F30 -G2 X4.8089 Y8.2462 I0.0287 J-0.2609 F10 -G1 X4.7802 Y8.267 -G1 X4.7515 Y8.2462 -G1 X4.705 Y8.2742 F10 -G2 X4.6818 Y8.2595 I-0.1249 J0.1719 F10 -G2 X4.5961 Y8.1159 I-0.2106 J0.0282 -G1 X4.5209 Y8.0612 -G1 X4.5496 Y7.9728 -G2 X4.5511 Y7.968 I-0.2021 J-0.0657 -G1 X4.5781 Y8.051 -G2 X4.9833 Y8.0479 I0.2021 J-0.0657 -G1 X5.0086 Y7.9658 -G2 X5.0107 Y7.9727 I0.2042 J-0.0587 -G1 X5.0395 Y8.0612 -G1 X4.9642 Y8.1159 -G2 X4.8785 Y8.2596 I0.1249 J0.1719 -G2 X4.8554 Y8.2742 I0.1019 J0.1865 -G1 X4.7802 Y8.3288 -G1 X4.705 Y8.2742 -G1 X4.6756 Y8.3146 F10 -G2 X4.6336 Y8.2927 I-0.0955 J0.1315 F10 -G2 X4.6337 Y8.2878 I-0.1624 J-0.0049 -G2 X4.5667 Y8.1563 I-0.1625 J0 -G1 X4.4621 Y8.0803 -G1 X4.5021 Y7.9573 -G2 X4.51 Y7.9124 I-0.1545 J-0.0503 -G1 X4.5856 Y7.9124 -G1 X4.6257 Y8.0355 -G2 X4.9355 Y8.0332 I0.1545 J-0.0502 -G1 X4.9728 Y7.9124 -G1 X5.0504 Y7.9124 -G2 X5.0583 Y7.9573 I0.1624 J-0.0053 -G1 X5.0982 Y8.0803 -G1 X4.9936 Y8.1563 -G2 X4.9266 Y8.2878 I0.0955 J0.1315 -G2 X4.9267 Y8.2927 I0.1625 J0 -G2 X4.8848 Y8.3146 I0.0537 J0.1534 -G1 X4.7802 Y8.3907 -G1 X4.6756 Y8.3146 -G1 X4.6462 Y8.3551 F10 -G2 X4.5738 Y8.3338 I-0.0661 J0.091 F10 -G2 X4.5837 Y8.2878 I-0.1027 J-0.046 -G2 X4.5373 Y8.1968 I-0.1125 J0 -G1 X4.4033 Y8.0994 -G1 X4.4546 Y7.9419 -G2 X4.4601 Y7.9071 I-0.107 J-0.0348 -G2 X4.4507 Y7.8622 I-0.1125 J0 -G2 X4.4563 Y7.8624 I0.0056 J-0.1124 -G1 X4.622 Y7.8624 -G1 X4.6732 Y8.02 -G2 X4.8877 Y8.0184 I0.107 J-0.0348 -G1 X4.9359 Y7.8624 -G1 X5.104 Y7.8624 -G2 X5.1097 Y7.8622 I0 J-0.1125 -G2 X5.1003 Y7.9071 I0.1032 J0.0449 -G2 X5.1058 Y7.9418 I0.1125 J0 -G1 X5.157 Y8.0994 -G1 X5.023 Y8.1968 -G2 X4.9766 Y8.2878 I0.0661 J0.091 -G2 X4.9864 Y8.3338 I0.1125 J0 -G2 X4.9142 Y8.3551 I-0.0061 J0.1123 -G1 X4.7802 Y8.4525 -G1 X4.6462 Y8.3551 -G0 Z0.25 -G0 X2.2203 Y8.2462 -G1 Z-0.05 F30 -G2 X2.2777 Y8.2462 I0.0287 J-0.2609 F10 -G1 X2.249 Y8.267 -G1 X2.2203 Y8.2462 -G1 X2.1737 Y8.2742 F10 -G2 X2.1505 Y8.2595 I-0.1249 J0.1719 F10 -G2 X2.0648 Y8.1159 I-0.2106 J0.0282 -G1 X1.9896 Y8.0612 -G1 X2.0184 Y7.9728 -G2 X2.0199 Y7.968 I-0.2021 J-0.0657 -G1 X2.0469 Y8.051 -G2 X2.452 Y8.0479 I0.2021 J-0.0657 -G1 X2.4774 Y7.9658 -G2 X2.4795 Y7.9727 I0.2042 J-0.0587 -G1 X2.5082 Y8.0612 -G1 X2.4329 Y8.1159 -G2 X2.3472 Y8.2596 I0.1249 J0.1719 -G2 X2.3242 Y8.2742 I0.1019 J0.1865 -G1 X2.249 Y8.3288 -G1 X2.1737 Y8.2742 -G1 X2.1443 Y8.3146 F10 -G2 X2.1024 Y8.2927 I-0.0955 J0.1315 F10 -G2 X2.1024 Y8.2878 I-0.1624 J-0.0049 -G2 X2.0354 Y8.1563 I-0.1625 J0 -G1 X1.9309 Y8.0803 -G1 X1.9709 Y7.9573 -G2 X1.9787 Y7.9124 I-0.1545 J-0.0503 -G1 X2.0544 Y7.9124 -G1 X2.0944 Y8.0355 -G2 X2.4042 Y8.0332 I0.1545 J-0.0502 -G1 X2.4415 Y7.9124 -G1 X2.5192 Y7.9124 -G2 X2.527 Y7.9573 I0.1624 J-0.0053 -G1 X2.567 Y8.0803 -G1 X2.4623 Y8.1563 -G2 X2.3953 Y8.2878 I0.0955 J0.1315 -G2 X2.3954 Y8.2927 I0.1625 J0 -G2 X2.3536 Y8.3146 I0.0537 J0.1534 -G1 X2.249 Y8.3907 -G1 X2.1443 Y8.3146 -G1 X2.1149 Y8.3551 F10 -G2 X2.0426 Y8.3338 I-0.0661 J0.091 F10 -G2 X2.0524 Y8.2878 I-0.1027 J-0.046 -G2 X2.0061 Y8.1968 I-0.1125 J0 -G1 X1.8721 Y8.0994 -G1 X1.9233 Y7.9419 -G2 X1.9288 Y7.9071 I-0.107 J-0.0348 -G2 X1.9195 Y7.8622 I-0.1125 J0 -G2 X1.9251 Y7.8624 I0.0056 J-0.1124 -G1 X2.0907 Y7.8624 -G1 X2.142 Y8.02 -G2 X2.3565 Y8.0184 I0.107 J-0.0348 -G1 X2.4046 Y7.8624 -G1 X2.5727 Y7.8624 -G2 X2.5784 Y7.8622 I0 J-0.1125 -G2 X2.5691 Y7.9071 I0.1032 J0.0449 -G2 X2.5746 Y7.9418 I0.1125 J0 -G1 X2.6258 Y8.0994 -G1 X2.4917 Y8.1968 -G2 X2.4453 Y8.2878 I0.0661 J0.091 -G2 X2.4552 Y8.3338 I0.1125 J0 -G2 X2.383 Y8.3551 I-0.0061 J0.1123 -G1 X2.249 Y8.4525 -G1 X2.1149 Y8.3551 -G0 Z0.25 -G0 X6.0171 Y8.2462 -G1 Z-0.05 F30 -G2 X6.0745 Y8.2462 I0.0287 J-0.2609 F10 -G1 X6.0458 Y8.267 -G1 X6.0171 Y8.2462 -G1 X5.9705 Y8.2742 F10 -G2 X5.9475 Y8.2596 I-0.1249 J0.1719 F10 -G2 X5.8618 Y8.1159 I-0.2106 J0.0282 -G1 X5.7865 Y8.0612 -G1 X5.8152 Y7.9727 -G2 X5.8167 Y7.9679 I-0.2021 J-0.0656 -G1 X5.8436 Y8.0509 -G2 X6.2488 Y8.048 I0.2021 J-0.0656 -G1 X6.2742 Y7.9658 -G2 X6.2763 Y7.9728 I0.2042 J-0.0588 -G1 X6.3051 Y8.0612 -G1 X6.2299 Y8.1159 -G2 X6.1442 Y8.2595 I0.1249 J0.1719 -G2 X6.121 Y8.2742 I0.1017 J0.1866 -G1 X6.0458 Y8.3288 -G1 X5.9705 Y8.2742 -G1 X5.9411 Y8.3146 F10 -G2 X5.8993 Y8.2927 I-0.0955 J0.1315 F10 -G2 X5.8994 Y8.2878 I-0.1624 J-0.005 -G2 X5.8324 Y8.1563 I-0.1625 J0 -G1 X5.7277 Y8.0803 -G1 X5.7677 Y7.9573 -G2 X5.7755 Y7.9124 I-0.1546 J-0.0502 -G1 X5.8513 Y7.9124 -G1 X5.8912 Y8.0354 -G2 X6.201 Y8.0333 I0.1546 J-0.0502 -G1 X6.2384 Y7.9124 -G1 X6.316 Y7.9124 -G2 X6.3239 Y7.9573 I0.1624 J-0.0053 -G1 X6.3639 Y8.0803 -G1 X6.2593 Y8.1563 -G2 X6.1923 Y8.2878 I0.0955 J0.1315 -G2 X6.1924 Y8.2927 I0.1625 J0 -G2 X6.1504 Y8.3146 I0.0535 J0.1534 -G1 X6.0458 Y8.3907 -G1 X5.9411 Y8.3146 -G1 X5.9118 Y8.3551 F10 -G2 X5.8395 Y8.3338 I-0.0661 J0.091 F10 -G2 X5.8494 Y8.2878 I-0.1027 J-0.046 -G2 X5.803 Y8.1968 I-0.1125 J0 -G1 X5.669 Y8.0994 -G1 X5.7201 Y7.9418 -G2 X5.7256 Y7.9071 I-0.107 J-0.0347 -G2 X5.7163 Y7.8622 I-0.1125 J0 -G2 X5.722 Y7.8624 I0.0057 J-0.1124 -G1 X5.8876 Y7.8624 -G1 X5.9388 Y8.02 -G2 X6.1532 Y8.0185 I0.107 J-0.0347 -G1 X6.2015 Y7.8624 -G1 X6.3697 Y7.8624 -G2 X6.3752 Y7.8622 I0 J-0.1125 -G2 X6.3659 Y7.9071 I0.1032 J0.0449 -G2 X6.3714 Y7.9419 I0.1125 J0 -G1 X6.4227 Y8.0994 -G1 X6.2887 Y8.1968 -G2 X6.2423 Y8.2878 I0.0661 J0.091 -G2 X6.2521 Y8.3338 I0.1125 J0 -G2 X6.1798 Y8.3551 I-0.0062 J0.1123 -G1 X6.0458 Y8.4525 -G1 X5.9118 Y8.3551 -G0 Z0.25 -G0 X3.4858 Y8.2462 -G1 Z-0.05 F30 -G2 X3.5432 Y8.2462 I0.0287 J-0.2609 F10 -G1 X3.5145 Y8.267 -G1 X3.4858 Y8.2462 -G1 X3.4393 Y8.2742 F10 -G2 X3.4163 Y8.2596 I-0.1249 J0.1719 F10 -G2 X3.3305 Y8.1159 I-0.2106 J0.0282 -G1 X3.2553 Y8.0612 -G1 X3.284 Y7.9727 -G2 X3.2855 Y7.9679 I-0.2021 J-0.0656 -G1 X3.3124 Y8.0509 -G2 X3.7175 Y8.048 I0.2021 J-0.0656 -G1 X3.7429 Y7.9658 -G2 X3.7451 Y7.9728 I0.2042 J-0.0588 -G1 X3.7738 Y8.0612 -G1 X3.6986 Y8.1159 -G2 X3.6129 Y8.2595 I0.1249 J0.1719 -G2 X3.5897 Y8.2742 I0.1017 J0.1866 -G1 X3.5145 Y8.3288 -G1 X3.4393 Y8.2742 -G1 X3.4099 Y8.3146 F10 -G2 X3.368 Y8.2927 I-0.0955 J0.1315 F10 -G2 X3.3681 Y8.2878 I-0.1624 J-0.005 -G2 X3.3011 Y8.1563 I-0.1625 J0 -G1 X3.1965 Y8.0803 -G1 X3.2364 Y7.9573 -G2 X3.2443 Y7.9124 I-0.1546 J-0.0502 -G1 X3.32 Y7.9124 -G1 X3.3599 Y8.0354 -G2 X3.6698 Y8.0333 I0.1546 J-0.0502 -G1 X3.7071 Y7.9124 -G1 X3.7847 Y7.9124 -G2 X3.7926 Y7.9573 I0.1624 J-0.0053 -G1 X3.8326 Y8.0803 -G1 X3.728 Y8.1563 -G2 X3.661 Y8.2878 I0.0955 J0.1315 -G2 X3.6611 Y8.2927 I0.1625 J0 -G2 X3.6191 Y8.3146 I0.0535 J0.1534 -G1 X3.5145 Y8.3907 -G1 X3.4099 Y8.3146 -G1 X3.3805 Y8.3551 F10 -G2 X3.3083 Y8.3338 I-0.0661 J0.091 F10 -G2 X3.3181 Y8.2878 I-0.1027 J-0.046 -G2 X3.2718 Y8.1968 I-0.1125 J0 -G1 X3.1377 Y8.0994 -G1 X3.1889 Y7.9418 -G2 X3.1944 Y7.9071 I-0.107 J-0.0347 -G2 X3.185 Y7.8622 I-0.1125 J0 -G2 X3.1908 Y7.8624 I0.0057 J-0.1124 -G1 X3.3564 Y7.8624 -G1 X3.4075 Y8.02 -G2 X3.622 Y8.0185 I0.107 J-0.0347 -G1 X3.6703 Y7.8624 -G1 X3.8384 Y7.8624 -G2 X3.844 Y7.8622 I0 J-0.1125 -G2 X3.8347 Y7.9071 I0.1032 J0.0449 -G2 X3.8402 Y7.9419 I0.1125 J0 -G1 X3.8914 Y8.0994 -G1 X3.7574 Y8.1968 -G2 X3.711 Y8.2878 I0.0661 J0.091 -G2 X3.7209 Y8.3338 I0.1125 J0 -G2 X3.6485 Y8.3551 I-0.0062 J0.1123 -G1 X3.5145 Y8.4525 -G1 X3.3805 Y8.3551 -G0 Z0.25 -G0 X4.7495 Y6.0885 -G1 Z-0.05 F30 -G2 X4.8109 Y6.0885 I0.0307 J-0.2607 F10 -G1 X4.7802 Y6.1108 -G1 X4.7495 Y6.0885 -G1 X4.705 Y6.1179 F10 -G2 X4.6818 Y6.1033 I-0.1249 J0.1719 F10 -G2 X4.5961 Y5.9596 I-0.2106 J0.0282 -G1 X4.5209 Y5.905 -G1 X4.5496 Y5.8166 -G2 X4.5513 Y5.8111 I-0.2021 J-0.0657 -G1 X4.5781 Y5.8935 -G2 X4.9833 Y5.8905 I0.2021 J-0.0657 -G1 X5.0084 Y5.8089 -G2 X5.0107 Y5.8164 I0.2044 J-0.0581 -G1 X5.0395 Y5.9049 -G1 X4.9642 Y5.9596 -G2 X4.8785 Y6.1034 I0.1249 J0.1719 -G2 X4.8554 Y6.1179 I0.1019 J0.1865 -G1 X4.7802 Y6.1726 -G1 X4.705 Y6.1179 -G1 X4.6756 Y6.1584 F10 -G2 X4.6336 Y6.1364 I-0.0955 J0.1315 F10 -G2 X4.6337 Y6.1315 I-0.1624 J-0.0049 -G2 X4.5667 Y6.0001 I-0.1625 J0 -G1 X4.4621 Y5.9241 -G1 X4.5021 Y5.8011 -G2 X4.51 Y5.755 I-0.1545 J-0.0503 -G1 X4.5857 Y5.755 -G1 X4.6257 Y5.878 -G2 X4.9355 Y5.8757 I0.1545 J-0.0503 -G1 X4.9727 Y5.755 -G1 X5.0504 Y5.755 -G2 X5.0583 Y5.801 I0.1624 J-0.0042 -G1 X5.0982 Y5.924 -G1 X4.9936 Y6.0001 -G2 X4.9266 Y6.1315 I0.0955 J0.1315 -G2 X4.9267 Y6.1365 I0.1625 J0 -G2 X4.8848 Y6.1584 I0.0537 J0.1534 -G1 X4.7802 Y6.2344 -G1 X4.6756 Y6.1584 -G1 X4.6462 Y6.1988 F10 -G2 X4.5738 Y6.1775 I-0.0661 J0.091 F10 -G2 X4.5837 Y6.1315 I-0.1027 J-0.046 -G2 X4.5373 Y6.0405 I-0.1125 J0 -G1 X4.4033 Y5.9431 -G1 X4.4546 Y5.7856 -G2 X4.4601 Y5.7508 I-0.107 J-0.0348 -G2 X4.4502 Y5.7048 I-0.1125 J0 -G2 X4.4563 Y5.705 I0.0061 J-0.1123 -G1 X4.622 Y5.705 -G1 X4.6732 Y5.8626 -G2 X4.8877 Y5.861 I0.107 J-0.0348 -G1 X4.9359 Y5.705 -G1 X5.104 Y5.705 -G2 X5.1102 Y5.7048 I0 J-0.1125 -G2 X5.1003 Y5.7508 I0.1027 J0.046 -G2 X5.1058 Y5.7856 I0.1125 J0 -G1 X5.157 Y5.9431 -G1 X5.023 Y6.0405 -G2 X4.9766 Y6.1315 I0.0661 J0.091 -G2 X4.9864 Y6.1775 I0.1125 J0 -G2 X4.9142 Y6.1988 I-0.0061 J0.1123 -G1 X4.7802 Y6.2962 -G1 X4.6462 Y6.1988 -G0 Z0.25 -G0 X4.7474 Y7.1663 -G1 Z-0.05 F30 -G2 X4.813 Y7.1663 I0.0328 J-0.2604 F10 -G1 X4.7802 Y7.1901 -G1 X4.7474 Y7.1663 -G1 X4.705 Y7.1972 F10 -G2 X4.682 Y7.1827 I-0.1249 J0.1719 F10 -G2 X4.5961 Y7.0378 I-0.2108 J0.027 -G1 X4.5209 Y6.9832 -G1 X4.5496 Y6.8947 -G2 X4.5514 Y6.8892 I-0.2021 J-0.0657 -G1 X4.5781 Y6.9716 -G2 X4.9833 Y6.9685 I0.2021 J-0.0657 -G1 X5.0084 Y6.887 -G2 X5.0107 Y6.8946 I0.2044 J-0.058 -G1 X5.0395 Y6.9831 -G1 X4.9642 Y7.0378 -G2 X4.8783 Y7.1828 I0.1249 J0.1719 -G2 X4.8554 Y7.1972 I0.102 J0.1864 -G1 X4.7802 Y7.2519 -G1 X4.705 Y7.1972 -G1 X4.6756 Y7.2377 F10 -G2 X4.6336 Y7.2157 I-0.0955 J0.1315 F10 -G2 X4.6337 Y7.2097 I-0.1624 J-0.006 -G2 X4.5667 Y7.0782 I-0.1625 J0 -G1 X4.4621 Y7.0023 -G1 X4.5021 Y6.8793 -G2 X4.51 Y6.833 I-0.1545 J-0.0503 -G1 X4.5857 Y6.833 -G1 X4.6257 Y6.9561 -G2 X4.9355 Y6.9538 I0.1545 J-0.0503 -G1 X4.9727 Y6.833 -G1 X5.0504 Y6.833 -G2 X5.0583 Y6.8792 I0.1625 J-0.004 -G1 X5.0982 Y7.0022 -G1 X4.9936 Y7.0782 -G2 X4.9266 Y7.2097 I0.0955 J0.1315 -G2 X4.9267 Y7.2158 I0.1625 J0 -G2 X4.8848 Y7.2377 I0.0536 J0.1534 -G1 X4.7802 Y7.3137 -G1 X4.6756 Y7.2377 -G1 X4.6462 Y7.2781 F10 -G2 X4.5733 Y7.2569 I-0.0661 J0.091 F10 -G2 X4.5837 Y7.2097 I-0.1021 J-0.0471 -G2 X4.5373 Y7.1187 I-0.1125 J0 -G1 X4.4033 Y7.0213 -G1 X4.4546 Y6.8638 -G2 X4.4601 Y6.829 I-0.107 J-0.0348 -G2 X4.4502 Y6.7829 I-0.1125 J0 -G2 X4.4563 Y6.783 I0.0061 J-0.1123 -G1 X4.622 Y6.783 -G1 X4.6732 Y6.9406 -G2 X4.8877 Y6.939 I0.107 J-0.0348 -G1 X4.9359 Y6.783 -G1 X5.104 Y6.783 -G2 X5.1102 Y6.7829 I0 J-0.1125 -G2 X5.1003 Y6.829 I0.1026 J0.0461 -G2 X5.1058 Y6.8638 I0.1125 J0 -G1 X5.157 Y7.0213 -G1 X5.023 Y7.1187 -G2 X4.9766 Y7.2097 I0.0661 J0.091 -G2 X4.9869 Y7.2569 I0.1125 J0 -G2 X4.9142 Y7.2781 I-0.0066 J0.1123 -G1 X4.7802 Y7.3755 -G1 X4.6462 Y7.2781 -G0 Z0.25 -G0 X2.2162 Y9.3225 -G1 Z-0.05 F30 -G2 X2.2818 Y9.3225 I0.0328 J-0.2604 F10 -G1 X2.249 Y9.3464 -G1 X2.2162 Y9.3225 -G1 X2.1737 Y9.3535 F10 -G2 X2.1507 Y9.3389 I-0.1249 J0.1719 F10 -G2 X2.0648 Y9.194 I-0.2108 J0.027 -G1 X1.9896 Y9.1394 -G1 X2.0184 Y9.051 -G2 X2.0201 Y9.0455 I-0.2021 J-0.0657 -G1 X2.0469 Y9.1278 -G2 X2.452 Y9.1248 I0.2021 J-0.0657 -G1 X2.4772 Y9.0433 -G2 X2.4795 Y9.0509 I0.2044 J-0.058 -G1 X2.5082 Y9.1394 -G1 X2.4329 Y9.194 -G2 X2.3471 Y9.339 I0.1249 J0.1719 -G2 X2.3242 Y9.3535 I0.102 J0.1864 -G1 X2.249 Y9.4082 -G1 X2.1737 Y9.3535 -G1 X2.1443 Y9.3939 F10 -G2 X2.1023 Y9.372 I-0.0955 J0.1315 F10 -G2 X2.1024 Y9.366 I-0.1624 J-0.006 -G2 X2.0354 Y9.2345 I-0.1625 J0 -G1 X1.9309 Y9.1585 -G1 X1.9709 Y9.0355 -G2 X1.9788 Y8.9893 I-0.1545 J-0.0503 -G1 X2.0544 Y8.9893 -G1 X2.0944 Y9.1123 -G2 X2.4042 Y9.11 I0.1545 J-0.0503 -G1 X2.4415 Y8.9893 -G1 X2.5191 Y8.9893 -G2 X2.527 Y9.0354 I0.1625 J-0.004 -G1 X2.567 Y9.1585 -G1 X2.4623 Y9.2345 -G2 X2.3953 Y9.366 I0.0955 J0.1315 -G2 X2.3955 Y9.372 I0.1625 J0 -G2 X2.3536 Y9.3939 I0.0536 J0.1534 -G1 X2.249 Y9.47 -G1 X2.1443 Y9.3939 -G1 X2.1149 Y9.4344 F10 -G2 X2.0421 Y9.4131 I-0.0661 J0.091 F10 -G2 X2.0524 Y9.366 I-0.1021 J-0.0471 -G2 X2.0061 Y9.2749 I-0.1125 J0 -G1 X1.8721 Y9.1776 -G1 X1.9233 Y9.0201 -G2 X1.9288 Y8.9853 I-0.107 J-0.0348 -G2 X1.9189 Y8.9391 I-0.1125 J0 -G2 X1.9251 Y8.9393 I0.0061 J-0.1123 -G1 X2.0907 Y8.9393 -G1 X2.142 Y9.0969 -G2 X2.3565 Y9.0953 I0.107 J-0.0348 -G1 X2.4046 Y8.9393 -G1 X2.5727 Y8.9393 -G2 X2.579 Y8.9391 I0 J-0.1125 -G2 X2.5691 Y8.9853 I0.1026 J0.0461 -G2 X2.5746 Y9.02 I0.1125 J0 -G1 X2.6258 Y9.1776 -G1 X2.4917 Y9.2749 -G2 X2.4453 Y9.366 I0.0661 J0.091 -G2 X2.4557 Y9.4131 I0.1125 J0 -G2 X2.383 Y9.4344 I-0.0066 J0.1123 -G1 X2.249 Y9.5318 -G1 X2.1149 Y9.4344 -G0 Z0.25 -G0 X2.2162 Y7.1663 -G1 Z-0.05 F30 -G2 X2.2818 Y7.1663 I0.0328 J-0.2604 F10 -G1 X2.249 Y7.1901 -G1 X2.2162 Y7.1663 -G1 X2.1737 Y7.1972 F10 -G2 X2.1507 Y7.1827 I-0.1249 J0.1719 F10 -G2 X2.0648 Y7.0378 I-0.2108 J0.027 -G1 X1.9896 Y6.9832 -G1 X2.0184 Y6.8947 -G2 X2.0201 Y6.8892 I-0.2021 J-0.0657 -G1 X2.0469 Y6.9716 -G2 X2.452 Y6.9685 I0.2021 J-0.0657 -G1 X2.4772 Y6.887 -G2 X2.4795 Y6.8946 I0.2044 J-0.058 -G1 X2.5082 Y6.9831 -G1 X2.4329 Y7.0378 -G2 X2.3471 Y7.1828 I0.1249 J0.1719 -G2 X2.3242 Y7.1972 I0.102 J0.1864 -G1 X2.249 Y7.2519 -G1 X2.1737 Y7.1972 -G1 X2.1443 Y7.2377 F10 -G2 X2.1023 Y7.2157 I-0.0955 J0.1315 F10 -G2 X2.1024 Y7.2097 I-0.1624 J-0.006 -G2 X2.0354 Y7.0782 I-0.1625 J0 -G1 X1.9309 Y7.0023 -G1 X1.9709 Y6.8793 -G2 X1.9788 Y6.833 I-0.1545 J-0.0503 -G1 X2.0544 Y6.833 -G1 X2.0944 Y6.9561 -G2 X2.4042 Y6.9538 I0.1545 J-0.0503 -G1 X2.4415 Y6.833 -G1 X2.5191 Y6.833 -G2 X2.527 Y6.8792 I0.1625 J-0.004 -G1 X2.567 Y7.0022 -G1 X2.4623 Y7.0782 -G2 X2.3953 Y7.2097 I0.0955 J0.1315 -G2 X2.3955 Y7.2158 I0.1625 J0 -G2 X2.3536 Y7.2377 I0.0536 J0.1534 -G1 X2.249 Y7.3137 -G1 X2.1443 Y7.2377 -G1 X2.1149 Y7.2781 F10 -G2 X2.0421 Y7.2569 I-0.0661 J0.091 F10 -G2 X2.0524 Y7.2097 I-0.1021 J-0.0471 -G2 X2.0061 Y7.1187 I-0.1125 J0 -G1 X1.8721 Y7.0213 -G1 X1.9233 Y6.8638 -G2 X1.9288 Y6.829 I-0.107 J-0.0348 -G2 X1.9189 Y6.7829 I-0.1125 J0 -G2 X1.9251 Y6.783 I0.0061 J-0.1123 -G1 X2.0907 Y6.783 -G1 X2.142 Y6.9406 -G2 X2.3565 Y6.939 I0.107 J-0.0348 -G1 X2.4046 Y6.783 -G1 X2.5727 Y6.783 -G2 X2.579 Y6.7829 I0 J-0.1125 -G2 X2.5691 Y6.829 I0.1026 J0.0461 -G2 X2.5746 Y6.8638 I0.1125 J0 -G1 X2.6258 Y7.0213 -G1 X2.4917 Y7.1187 -G2 X2.4453 Y7.2097 I0.0661 J0.091 -G2 X2.4557 Y7.2569 I0.1125 J0 -G2 X2.383 Y7.2781 I-0.0066 J0.1123 -G1 X2.249 Y7.3755 -G1 X2.1149 Y7.2781 -G0 Z0.25 -G0 X4.7474 Y9.3225 -G1 Z-0.05 F30 -G2 X4.813 Y9.3225 I0.0328 J-0.2604 F10 -G1 X4.7802 Y9.3464 -G1 X4.7474 Y9.3225 -G1 X4.705 Y9.3535 F10 -G2 X4.682 Y9.3389 I-0.1249 J0.1719 F10 -G2 X4.5961 Y9.194 I-0.2108 J0.027 -G1 X4.5209 Y9.1394 -G1 X4.5496 Y9.051 -G2 X4.5514 Y9.0455 I-0.2021 J-0.0657 -G1 X4.5781 Y9.1278 -G2 X4.9833 Y9.1248 I0.2021 J-0.0657 -G1 X5.0084 Y9.0433 -G2 X5.0107 Y9.0509 I0.2044 J-0.058 -G1 X5.0395 Y9.1394 -G1 X4.9642 Y9.194 -G2 X4.8783 Y9.339 I0.1249 J0.1719 -G2 X4.8554 Y9.3535 I0.102 J0.1864 -G1 X4.7802 Y9.4082 -G1 X4.705 Y9.3535 -G1 X4.6756 Y9.3939 F10 -G2 X4.6336 Y9.372 I-0.0955 J0.1315 F10 -G2 X4.6337 Y9.366 I-0.1624 J-0.006 -G2 X4.5667 Y9.2345 I-0.1625 J0 -G1 X4.4621 Y9.1585 -G1 X4.5021 Y9.0355 -G2 X4.51 Y8.9893 I-0.1545 J-0.0503 -G1 X4.5857 Y8.9893 -G1 X4.6257 Y9.1123 -G2 X4.9355 Y9.11 I0.1545 J-0.0503 -G1 X4.9727 Y8.9893 -G1 X5.0504 Y8.9893 -G2 X5.0583 Y9.0354 I0.1625 J-0.004 -G1 X5.0982 Y9.1585 -G1 X4.9936 Y9.2345 -G2 X4.9266 Y9.366 I0.0955 J0.1315 -G2 X4.9267 Y9.372 I0.1625 J0 -G2 X4.8848 Y9.3939 I0.0536 J0.1534 -G1 X4.7802 Y9.47 -G1 X4.6756 Y9.3939 -G1 X4.6462 Y9.4344 F10 -G2 X4.5733 Y9.4131 I-0.0661 J0.091 F10 -G2 X4.5837 Y9.366 I-0.1021 J-0.0471 -G2 X4.5373 Y9.2749 I-0.1125 J0 -G1 X4.4033 Y9.1776 -G1 X4.4546 Y9.0201 -G2 X4.4601 Y8.9853 I-0.107 J-0.0348 -G2 X4.4502 Y8.9391 I-0.1125 J0 -G2 X4.4563 Y8.9393 I0.0061 J-0.1123 -G1 X4.622 Y8.9393 -G1 X4.6732 Y9.0969 -G2 X4.8877 Y9.0953 I0.107 J-0.0348 -G1 X4.9359 Y8.9393 -G1 X5.104 Y8.9393 -G2 X5.1102 Y8.9391 I0 J-0.1125 -G2 X5.1003 Y8.9853 I0.1026 J0.0461 -G2 X5.1058 Y9.02 I0.1125 J0 -G1 X5.157 Y9.1776 -G1 X5.023 Y9.2749 -G2 X4.9766 Y9.366 I0.0661 J0.091 -G2 X4.9869 Y9.4131 I0.1125 J0 -G2 X4.9142 Y9.4344 I-0.0066 J0.1123 -G1 X4.7802 Y9.5318 -G1 X4.6462 Y9.4344 -G0 Z0.25 -G0 X2.2182 Y6.0885 -G1 Z-0.05 F30 -G2 X2.2797 Y6.0885 I0.0307 J-0.2607 F10 -G1 X2.249 Y6.1108 -G1 X2.2182 Y6.0885 -G1 X2.1737 Y6.1179 F10 -G2 X2.1505 Y6.1033 I-0.1249 J0.1719 F10 -G2 X2.0648 Y5.9596 I-0.2106 J0.0282 -G1 X1.9896 Y5.905 -G1 X2.0184 Y5.8166 -G2 X2.0201 Y5.8111 I-0.2021 J-0.0657 -G1 X2.0469 Y5.8935 -G2 X2.452 Y5.8905 I0.2021 J-0.0657 -G1 X2.4772 Y5.8089 -G2 X2.4795 Y5.8164 I0.2044 J-0.0581 -G1 X2.5082 Y5.9049 -G1 X2.4329 Y5.9596 -G2 X2.3472 Y6.1034 I0.1249 J0.1719 -G2 X2.3242 Y6.1179 I0.1019 J0.1865 -G1 X2.249 Y6.1726 -G1 X2.1737 Y6.1179 -G1 X2.1443 Y6.1584 F10 -G2 X2.1024 Y6.1364 I-0.0955 J0.1315 F10 -G2 X2.1024 Y6.1315 I-0.1624 J-0.0049 -G2 X2.0354 Y6.0001 I-0.1625 J0 -G1 X1.9309 Y5.9241 -G1 X1.9709 Y5.8011 -G2 X1.9788 Y5.755 I-0.1545 J-0.0503 -G1 X2.0544 Y5.755 -G1 X2.0944 Y5.878 -G2 X2.4042 Y5.8757 I0.1545 J-0.0503 -G1 X2.4415 Y5.755 -G1 X2.5192 Y5.755 -G2 X2.527 Y5.801 I0.1624 J-0.0042 -G1 X2.567 Y5.924 -G1 X2.4623 Y6.0001 -G2 X2.3953 Y6.1315 I0.0955 J0.1315 -G2 X2.3954 Y6.1365 I0.1625 J0 -G2 X2.3536 Y6.1584 I0.0537 J0.1534 -G1 X2.249 Y6.2344 -G1 X2.1443 Y6.1584 -G1 X2.1149 Y6.1988 F10 -G2 X2.0426 Y6.1775 I-0.0661 J0.091 F10 -G2 X2.0524 Y6.1315 I-0.1027 J-0.046 -G2 X2.0061 Y6.0405 I-0.1125 J0 -G1 X1.8721 Y5.9431 -G1 X1.9233 Y5.7856 -G2 X1.9288 Y5.7508 I-0.107 J-0.0348 -G2 X1.919 Y5.7048 I-0.1125 J0 -G2 X1.9251 Y5.705 I0.0061 J-0.1123 -G1 X2.0907 Y5.705 -G1 X2.142 Y5.8626 -G2 X2.3565 Y5.861 I0.107 J-0.0348 -G1 X2.4046 Y5.705 -G1 X2.5727 Y5.705 -G2 X2.5789 Y5.7048 I0 J-0.1125 -G2 X2.5691 Y5.7508 I0.1027 J0.046 -G2 X2.5746 Y5.7856 I0.1125 J0 -G1 X2.6258 Y5.9431 -G1 X2.4917 Y6.0405 -G2 X2.4453 Y6.1315 I0.0661 J0.091 -G2 X2.4552 Y6.1775 I0.1125 J0 -G2 X2.383 Y6.1988 I-0.0061 J0.1123 -G1 X2.249 Y6.2962 -G1 X2.1149 Y6.1988 -G0 Z0.25 -G0 X1.585 Y6.6274 -G1 Z-0.05 F30 -G2 X1.6471 Y6.6275 I0.0311 J-0.2606 F10 -G1 X1.6161 Y6.65 -G1 X1.585 Y6.6274 -G1 X1.5408 Y6.6571 F10 -G2 X1.5178 Y6.6425 I-0.1249 J0.1719 F10 -G2 X1.4321 Y6.4986 I-0.2106 J0.028 -G1 X1.3568 Y6.4439 -G1 X1.3855 Y6.3555 -G2 X1.3872 Y6.3499 I-0.2021 J-0.0656 -G1 X1.4141 Y6.4325 -G2 X1.8192 Y6.4295 I0.2021 J-0.0657 -G1 X1.8444 Y6.3479 -G2 X1.8467 Y6.3555 I0.2044 J-0.0581 -G1 X1.8754 Y6.4439 -G1 X1.8002 Y6.4986 -G2 X1.7144 Y6.6425 I0.1249 J0.1719 -G2 X1.6915 Y6.6571 I0.1019 J0.1865 -G1 X1.6161 Y6.7118 -G1 X1.5408 Y6.6571 -G1 X1.5114 Y6.6976 F10 -G2 X1.4696 Y6.6756 I-0.0955 J0.1315 F10 -G2 X1.4697 Y6.6705 I-0.1624 J-0.0051 -G2 X1.4027 Y6.5391 I-0.1625 J0 -G1 X1.298 Y6.463 -G1 X1.338 Y6.34 -G2 X1.3458 Y6.294 I-0.1546 J-0.0502 -G1 X1.4216 Y6.294 -G1 X1.4616 Y6.4171 -G2 X1.7714 Y6.4147 I0.1545 J-0.0503 -G1 X1.8087 Y6.294 -G1 X1.8864 Y6.294 -G2 X1.8943 Y6.34 I0.1624 J-0.0042 -G1 X1.9342 Y6.463 -G1 X1.8296 Y6.5391 -G2 X1.7626 Y6.6705 I0.0955 J0.1315 -G2 X1.7626 Y6.6756 I0.1625 J0 -G2 X1.7208 Y6.6975 I0.0537 J0.1534 -G1 X1.6161 Y6.7736 -G1 X1.5114 Y6.6976 -G1 X1.482 Y6.738 F10 -G2 X1.4098 Y6.7167 I-0.0661 J0.091 F10 -G2 X1.4197 Y6.6705 I-0.1026 J-0.0461 -G2 X1.3733 Y6.5795 I-0.1125 J0 -G1 X1.2392 Y6.4821 -G1 X1.2904 Y6.3246 -G2 X1.2959 Y6.2899 I-0.107 J-0.0347 -G2 X1.2861 Y6.2438 I-0.1125 J0 -G2 X1.2923 Y6.244 I0.0062 J-0.1123 -G1 X1.4579 Y6.244 -G1 X1.5092 Y6.4016 -G2 X1.7237 Y6.4 I0.107 J-0.0348 -G1 X1.7718 Y6.244 -G1 X1.9399 Y6.244 -G2 X1.9462 Y6.2438 I0 J-0.1125 -G2 X1.9363 Y6.2899 I0.1027 J0.046 -G2 X1.9418 Y6.3246 I0.1125 J0 -G1 X1.993 Y6.4821 -G1 X1.8589 Y6.5795 -G2 X1.8126 Y6.6705 I0.0661 J0.091 -G2 X1.8225 Y6.7167 I0.1125 J0 -G2 X1.7502 Y6.738 I-0.0061 J0.1123 -G1 X1.6161 Y6.8354 -G1 X1.482 Y6.738 -G0 Z0.25 -G0 X1.585 Y8.7837 -G1 Z-0.05 F30 -G2 X1.6471 Y8.7837 I0.0311 J-0.2606 F10 -G1 X1.6161 Y8.8063 -G1 X1.585 Y8.7837 -G1 X1.5408 Y8.8134 F10 -G2 X1.5178 Y8.7988 I-0.1249 J0.1719 F10 -G2 X1.4321 Y8.6549 I-0.2106 J0.028 -G1 X1.3568 Y8.6002 -G1 X1.3855 Y8.5117 -G2 X1.3872 Y8.5062 I-0.2021 J-0.0656 -G1 X1.4141 Y8.5888 -G2 X1.8192 Y8.5857 I0.2021 J-0.0657 -G1 X1.8444 Y8.5042 -G2 X1.8467 Y8.5117 I0.2044 J-0.0581 -G1 X1.8754 Y8.6002 -G1 X1.8002 Y8.6549 -G2 X1.7144 Y8.7988 I0.1249 J0.1719 -G2 X1.6915 Y8.8133 I0.1019 J0.1865 -G1 X1.6161 Y8.868 -G1 X1.5408 Y8.8134 -G1 X1.5114 Y8.8538 F10 -G2 X1.4696 Y8.8319 I-0.0955 J0.1315 F10 -G2 X1.4697 Y8.8268 I-0.1624 J-0.0051 -G2 X1.4027 Y8.6953 I-0.1625 J0 -G1 X1.298 Y8.6193 -G1 X1.338 Y8.4963 -G2 X1.3458 Y8.4503 I-0.1546 J-0.0502 -G1 X1.4216 Y8.4503 -G1 X1.4616 Y8.5733 -G2 X1.7714 Y8.571 I0.1545 J-0.0503 -G1 X1.8087 Y8.4503 -G1 X1.8864 Y8.4503 -G2 X1.8943 Y8.4963 I0.1624 J-0.0042 -G1 X1.9342 Y8.6193 -G1 X1.8296 Y8.6953 -G2 X1.7626 Y8.8268 I0.0955 J0.1315 -G2 X1.7626 Y8.8319 I0.1625 J0 -G2 X1.7208 Y8.8538 I0.0537 J0.1534 -G1 X1.6161 Y8.9298 -G1 X1.5114 Y8.8538 -G1 X1.482 Y8.8943 F10 -G2 X1.4098 Y8.8729 I-0.0661 J0.091 F10 -G2 X1.4197 Y8.8268 I-0.1026 J-0.0461 -G2 X1.3733 Y8.7358 I-0.1125 J0 -G1 X1.2392 Y8.6384 -G1 X1.2904 Y8.4808 -G2 X1.2959 Y8.4461 I-0.107 J-0.0347 -G2 X1.2861 Y8.4001 I-0.1125 J0 -G2 X1.2923 Y8.4003 I0.0062 J-0.1123 -G1 X1.4579 Y8.4003 -G1 X1.5092 Y8.5578 -G2 X1.7237 Y8.5562 I0.107 J-0.0348 -G1 X1.7718 Y8.4003 -G1 X1.9399 Y8.4003 -G2 X1.9462 Y8.4001 I0 J-0.1125 -G2 X1.9363 Y8.4461 I0.1027 J0.046 -G2 X1.9418 Y8.4808 I0.1125 J0 -G1 X1.993 Y8.6384 -G1 X1.8589 Y8.7358 -G2 X1.8126 Y8.8268 I0.0661 J0.091 -G2 X1.8225 Y8.8729 I0.1125 J0 -G2 X1.7502 Y8.8942 I-0.0061 J0.1123 -G1 X1.6161 Y8.9916 -G1 X1.482 Y8.8943 -G0 Z0.25 -G0 X5.382 Y8.7837 -G1 Z-0.05 F30 -G2 X5.444 Y8.7837 I0.031 J-0.2607 F10 -G1 X5.413 Y8.8062 -G1 X5.382 Y8.7837 -G1 X5.3378 Y8.8134 F10 -G2 X5.3146 Y8.7987 I-0.1249 J0.1719 F10 -G2 X5.2289 Y8.6549 I-0.2106 J0.0281 -G1 X5.1537 Y8.6002 -G1 X5.1824 Y8.5118 -G2 X5.1841 Y8.5063 I-0.2021 J-0.0657 -G1 X5.2109 Y8.5887 -G2 X5.616 Y8.5858 I0.2021 J-0.0656 -G1 X5.6412 Y8.5042 -G2 X5.6435 Y8.5118 I0.2044 J-0.0581 -G1 X5.6723 Y8.6002 -G1 X5.5971 Y8.6549 -G2 X5.5114 Y8.7987 I0.1249 J0.1719 -G2 X5.4882 Y8.8134 I0.1017 J0.1866 -G1 X5.413 Y8.868 -G1 X5.3378 Y8.8134 -G1 X5.3084 Y8.8538 F10 -G2 X5.2664 Y8.8318 I-0.0955 J0.1315 F10 -G2 X5.2665 Y8.8268 I-0.1624 J-0.005 -G2 X5.1995 Y8.6953 I-0.1625 J0 -G1 X5.0949 Y8.6193 -G1 X5.1349 Y8.4964 -G2 X5.1428 Y8.4503 I-0.1545 J-0.0503 -G1 X5.2185 Y8.4503 -G1 X5.2584 Y8.5732 -G2 X5.5682 Y8.5711 I0.1546 J-0.0502 -G1 X5.6056 Y8.4503 -G1 X5.6832 Y8.4503 -G2 X5.6911 Y8.4964 I0.1624 J-0.0042 -G1 X5.7311 Y8.6193 -G1 X5.6265 Y8.6953 -G2 X5.5595 Y8.8268 I0.0955 J0.1315 -G2 X5.5596 Y8.8318 I0.1625 J0 -G2 X5.5176 Y8.8538 I0.0535 J0.1534 -G1 X5.413 Y8.9298 -G1 X5.3084 Y8.8538 -G1 X5.279 Y8.8943 F10 -G2 X5.2066 Y8.8729 I-0.0661 J0.091 F10 -G2 X5.2165 Y8.8268 I-0.1026 J-0.0461 -G2 X5.1701 Y8.7358 I-0.1125 J0 -G1 X5.0361 Y8.6384 -G1 X5.0873 Y8.4809 -G2 X5.0928 Y8.4461 I-0.107 J-0.0348 -G2 X5.083 Y8.4001 I-0.1125 J0 -G2 X5.0891 Y8.4003 I0.0061 J-0.1123 -G1 X5.2548 Y8.4003 -G1 X5.306 Y8.5578 -G2 X5.5205 Y8.5563 I0.107 J-0.0347 -G1 X5.5687 Y8.4003 -G1 X5.7369 Y8.4003 -G2 X5.743 Y8.4001 I0 J-0.1125 -G2 X5.7331 Y8.4461 I0.1027 J0.046 -G2 X5.7386 Y8.4809 I0.1125 J0 -G1 X5.7899 Y8.6384 -G1 X5.6559 Y8.7358 -G2 X5.6095 Y8.8268 I0.0661 J0.091 -G2 X5.6194 Y8.8729 I0.1125 J0 -G2 X5.547 Y8.8943 I-0.0063 J0.1123 -G1 X5.413 Y8.9916 -G1 X5.279 Y8.8943 -G0 Z0.25 -G0 X6.6476 Y6.6275 -G1 Z-0.05 F30 -G2 X6.7097 Y6.6274 I0.031 J-0.2607 F10 -G1 X6.6786 Y6.65 -G1 X6.6476 Y6.6275 -G1 X6.6033 Y6.6571 F10 -G2 X6.5803 Y6.6425 I-0.1249 J0.1719 F10 -G2 X6.4946 Y6.4986 I-0.2106 J0.028 -G1 X6.4193 Y6.4439 -G1 X6.448 Y6.3555 -G2 X6.4497 Y6.3501 I-0.2021 J-0.0656 -G1 X6.4764 Y6.4324 -G2 X6.8816 Y6.4296 I0.2021 J-0.0656 -G1 X6.9069 Y6.3478 -G2 X6.9092 Y6.3555 I0.2045 J-0.0579 -G1 X6.9379 Y6.4439 -G1 X6.8627 Y6.4986 -G2 X6.7769 Y6.6425 I0.1249 J0.1719 -G2 X6.754 Y6.6571 I0.1019 J0.1865 -G1 X6.6786 Y6.7118 -G1 X6.6033 Y6.6571 -G1 X6.5739 Y6.6976 F10 -G2 X6.5321 Y6.6756 I-0.0955 J0.1315 F10 -G2 X6.5322 Y6.6705 I-0.1624 J-0.0051 -G2 X6.4652 Y6.5391 I-0.1625 J0 -G1 X6.3605 Y6.463 -G1 X6.4005 Y6.34 -G2 X6.4083 Y6.294 I-0.1546 J-0.0502 -G1 X6.4841 Y6.294 -G1 X6.524 Y6.417 -G2 X6.8338 Y6.4148 I0.1546 J-0.0502 -G1 X6.8712 Y6.294 -G1 X6.9489 Y6.294 -G2 X6.9568 Y6.34 I0.1624 J-0.0042 -G1 X6.9967 Y6.463 -G1 X6.8921 Y6.5391 -G2 X6.8251 Y6.6705 I0.0955 J0.1315 -G2 X6.8251 Y6.6756 I0.1625 J0 -G2 X6.7833 Y6.6975 I0.0537 J0.1534 -G1 X6.6786 Y6.7736 -G1 X6.5739 Y6.6976 -G1 X6.5445 Y6.738 F10 -G2 X6.4723 Y6.7167 I-0.0661 J0.091 F10 -G2 X6.4822 Y6.6705 I-0.1026 J-0.0461 -G2 X6.4358 Y6.5795 I-0.1125 J0 -G1 X6.3017 Y6.4821 -G1 X6.3529 Y6.3246 -G2 X6.3584 Y6.2899 I-0.107 J-0.0347 -G2 X6.3486 Y6.2438 I-0.1125 J0 -G2 X6.3548 Y6.244 I0.0062 J-0.1123 -G1 X6.5204 Y6.244 -G1 X6.5715 Y6.4015 -G2 X6.786 Y6.4 I0.107 J-0.0347 -G1 X6.8343 Y6.244 -G1 X7.0024 Y6.244 -G2 X7.0087 Y6.2438 I0 J-0.1125 -G2 X6.9988 Y6.2899 I0.1027 J0.046 -G2 X7.0043 Y6.3246 I0.1125 J0 -G1 X7.0555 Y6.4821 -G1 X6.9214 Y6.5795 -G2 X6.8751 Y6.6705 I0.0661 J0.091 -G2 X6.885 Y6.7167 I0.1125 J0 -G2 X6.8127 Y6.738 I-0.0061 J0.1123 -G1 X6.6786 Y6.8354 -G1 X6.5445 Y6.738 -G0 Z0.25 -G0 X6.6478 Y7.7057 -G1 Z-0.05 F30 -G2 X6.7094 Y7.7057 I0.0307 J-0.2607 F10 -G1 X6.6786 Y7.7281 -G1 X6.6478 Y7.7057 -G1 X6.6033 Y7.7352 F10 -G2 X6.5801 Y7.7205 I-0.1249 J0.1719 F10 -G2 X6.4946 Y7.5779 I-0.2105 J0.0294 -G1 X6.4193 Y7.5232 -G1 X6.448 Y7.4348 -G2 X6.4499 Y7.4288 I-0.2021 J-0.0656 -G1 X6.4764 Y7.5106 -G2 X6.8816 Y7.5078 I0.2021 J-0.0656 -G1 X6.9067 Y7.4265 -G2 X6.9092 Y7.4348 I0.2046 J-0.0573 -G1 X6.9379 Y7.5232 -G1 X6.8627 Y7.5779 -G2 X6.7771 Y7.7205 I0.1249 J0.1719 -G2 X6.754 Y7.7351 I0.1017 J0.1866 -G1 X6.6786 Y7.7899 -G1 X6.6033 Y7.7352 -G1 X6.5739 Y7.7756 F10 -G2 X6.5321 Y7.7537 I-0.0955 J0.1315 F10 -G2 X6.5322 Y7.7499 I-0.1625 J-0.0039 -G2 X6.4652 Y7.6184 I-0.1625 J0 -G1 X6.3605 Y7.5424 -G1 X6.4005 Y7.4193 -G2 X6.4084 Y7.3722 I-0.1546 J-0.0502 -G1 X6.4841 Y7.3722 -G1 X6.524 Y7.4952 -G2 X6.8338 Y7.493 I0.1546 J-0.0502 -G1 X6.8712 Y7.3722 -G1 X6.9488 Y7.3722 -G2 X6.9568 Y7.4193 I0.1625 J-0.0031 -G1 X6.9967 Y7.5424 -G1 X6.8921 Y7.6184 -G2 X6.8251 Y7.7499 I0.0955 J0.1315 -G2 X6.8251 Y7.7537 I0.1625 J0 -G2 X6.7833 Y7.7756 I0.0537 J0.1534 -G1 X6.6786 Y7.8516 -G1 X6.5739 Y7.7756 -G1 X6.5445 Y7.8161 F10 -G2 X6.4728 Y7.7947 I-0.0661 J0.091 F10 -G2 X6.4822 Y7.7499 I-0.1032 J-0.0449 -G2 X6.4358 Y7.6588 I-0.1125 J0 -G1 X6.3017 Y7.5615 -G1 X6.3529 Y7.4039 -G2 X6.3584 Y7.3692 I-0.107 J-0.0347 -G2 X6.348 Y7.322 I-0.1125 J0 -G2 X6.3548 Y7.3222 I0.0067 J-0.1123 -G1 X6.5204 Y7.3222 -G1 X6.5715 Y7.4797 -G2 X6.786 Y7.4782 I0.107 J-0.0347 -G1 X6.8343 Y7.3222 -G1 X7.0024 Y7.3222 -G2 X7.0092 Y7.322 I0 J-0.1125 -G2 X6.9988 Y7.3692 I0.1021 J0.0471 -G2 X7.0043 Y7.4039 I0.1125 J0 -G1 X7.0555 Y7.5615 -G1 X6.9214 Y7.6588 -G2 X6.8751 Y7.7499 I0.0661 J0.091 -G2 X6.8844 Y7.7947 I0.1125 J0 -G2 X6.8127 Y7.816 I-0.0056 J0.1124 -G1 X6.6786 Y7.9134 -G1 X6.5445 Y7.8161 -G0 Z0.25 -G0 X5.382 Y6.6275 -G1 Z-0.05 F30 -G2 X5.444 Y6.6275 I0.031 J-0.2607 F10 -G1 X5.413 Y6.65 -G1 X5.382 Y6.6275 -G1 X5.3378 Y6.6571 F10 -G2 X5.3146 Y6.6425 I-0.1249 J0.1719 F10 -G2 X5.2289 Y6.4986 I-0.2106 J0.0281 -G1 X5.1537 Y6.444 -G1 X5.1824 Y6.3556 -G2 X5.1841 Y6.3501 I-0.2021 J-0.0657 -G1 X5.2109 Y6.4324 -G2 X5.616 Y6.4296 I0.2021 J-0.0656 -G1 X5.6412 Y6.348 -G2 X5.6435 Y6.3556 I0.2044 J-0.0581 -G1 X5.6723 Y6.444 -G1 X5.5971 Y6.4986 -G2 X5.5114 Y6.6425 I0.1249 J0.1719 -G2 X5.4882 Y6.6571 I0.1017 J0.1866 -G1 X5.413 Y6.7118 -G1 X5.3378 Y6.6571 -G1 X5.3084 Y6.6976 F10 -G2 X5.2664 Y6.6756 I-0.0955 J0.1315 F10 -G2 X5.2665 Y6.6705 I-0.1624 J-0.005 -G2 X5.1995 Y6.5391 I-0.1625 J0 -G1 X5.0949 Y6.4631 -G1 X5.1349 Y6.3401 -G2 X5.1428 Y6.294 I-0.1545 J-0.0503 -G1 X5.2185 Y6.294 -G1 X5.2584 Y6.417 -G2 X5.5682 Y6.4148 I0.1546 J-0.0502 -G1 X5.6056 Y6.294 -G1 X5.6832 Y6.294 -G2 X5.6911 Y6.3401 I0.1624 J-0.0042 -G1 X5.7311 Y6.4631 -G1 X5.6265 Y6.5391 -G2 X5.5595 Y6.6705 I0.0955 J0.1315 -G2 X5.5596 Y6.6756 I0.1625 J0 -G2 X5.5176 Y6.6976 I0.0535 J0.1534 -G1 X5.413 Y6.7736 -G1 X5.3084 Y6.6976 -G1 X5.279 Y6.738 F10 -G2 X5.2066 Y6.7167 I-0.0661 J0.091 F10 -G2 X5.2165 Y6.6705 I-0.1026 J-0.0461 -G2 X5.1701 Y6.5795 I-0.1125 J0 -G1 X5.0361 Y6.4822 -G1 X5.0873 Y6.3246 -G2 X5.0928 Y6.2899 I-0.107 J-0.0348 -G2 X5.083 Y6.2439 I-0.1125 J0 -G2 X5.0891 Y6.244 I0.0061 J-0.1123 -G1 X5.2548 Y6.244 -G1 X5.306 Y6.4015 -G2 X5.5205 Y6.4 I0.107 J-0.0347 -G1 X5.5687 Y6.244 -G1 X5.7369 Y6.244 -G2 X5.743 Y6.2439 I0 J-0.1125 -G2 X5.7331 Y6.2899 I0.1027 J0.046 -G2 X5.7386 Y6.3246 I0.1125 J0 -G1 X5.7899 Y6.4822 -G1 X5.6559 Y6.5795 -G2 X5.6095 Y6.6705 I0.0661 J0.091 -G2 X5.6194 Y6.7167 I0.1125 J0 -G2 X5.547 Y6.738 I-0.0063 J0.1123 -G1 X5.413 Y6.8354 -G1 X5.279 Y6.738 -G0 Z0.25 -G0 X4.1163 Y8.7837 -G1 Z-0.05 F30 -G2 X4.1784 Y8.7837 I0.031 J-0.2607 F10 -G1 X4.1473 Y8.8063 -G1 X4.1163 Y8.7837 -G1 X4.0721 Y8.8134 F10 -G2 X4.049 Y8.7988 I-0.1249 J0.1719 F10 -G2 X3.9633 Y8.6549 I-0.2106 J0.028 -G1 X3.888 Y8.6002 -G1 X3.9168 Y8.5117 -G2 X3.9184 Y8.5063 I-0.2021 J-0.0656 -G1 X3.9452 Y8.5887 -G2 X4.3503 Y8.5858 I0.2021 J-0.0656 -G1 X4.3756 Y8.504 -G2 X4.378 Y8.5117 I0.2045 J-0.0579 -G1 X4.4067 Y8.6002 -G1 X4.3314 Y8.6549 -G2 X4.2457 Y8.7988 I0.1249 J0.1719 -G2 X4.2227 Y8.8133 I0.1019 J0.1865 -G1 X4.1473 Y8.868 -G1 X4.0721 Y8.8134 -G1 X4.0427 Y8.8538 F10 -G2 X4.0008 Y8.8319 I-0.0955 J0.1315 F10 -G2 X4.0009 Y8.8268 I-0.1624 J-0.0051 -G2 X3.9339 Y8.6953 I-0.1625 J0 -G1 X3.8293 Y8.6193 -G1 X3.8692 Y8.4963 -G2 X3.8771 Y8.4503 I-0.1546 J-0.0502 -G1 X3.9528 Y8.4503 -G1 X3.9927 Y8.5732 -G2 X4.3025 Y8.5711 I0.1546 J-0.0502 -G1 X4.3399 Y8.4503 -G1 X4.4176 Y8.4503 -G2 X4.4255 Y8.4963 I0.1624 J-0.0042 -G1 X4.4655 Y8.6193 -G1 X4.3608 Y8.6953 -G2 X4.2938 Y8.8268 I0.0955 J0.1315 -G2 X4.2939 Y8.8319 I0.1625 J0 -G2 X4.2521 Y8.8538 I0.0537 J0.1534 -G1 X4.1473 Y8.9298 -G1 X4.0427 Y8.8538 -G1 X4.0133 Y8.8943 F10 -G2 X3.941 Y8.8729 I-0.0661 J0.091 F10 -G2 X3.9509 Y8.8268 I-0.1026 J-0.0461 -G2 X3.9045 Y8.7358 I-0.1125 J0 -G1 X3.7705 Y8.6384 -G1 X3.8217 Y8.4808 -G2 X3.8272 Y8.4461 I-0.107 J-0.0347 -G2 X3.8173 Y8.4001 I-0.1125 J0 -G2 X3.8235 Y8.4003 I0.0062 J-0.1123 -G1 X3.9891 Y8.4003 -G1 X4.0403 Y8.5578 -G2 X4.2548 Y8.5563 I0.107 J-0.0347 -G1 X4.303 Y8.4003 -G1 X4.4712 Y8.4003 -G2 X4.4774 Y8.4001 I0 J-0.1125 -G2 X4.4676 Y8.4461 I0.1027 J0.046 -G2 X4.4731 Y8.4808 I0.1125 J0 -G1 X4.5242 Y8.6384 -G1 X4.3902 Y8.7358 -G2 X4.3438 Y8.8268 I0.0661 J0.091 -G2 X4.3537 Y8.8729 I0.1125 J0 -G2 X4.2815 Y8.8942 I-0.0061 J0.1123 -G1 X4.1473 Y8.9916 -G1 X4.0133 Y8.8943 -G0 Z0.25 -G0 X3.4817 Y9.3225 -G1 Z-0.05 F30 -G2 X3.5473 Y9.3225 I0.0328 J-0.2604 F10 -G1 X3.5145 Y9.3464 -G1 X3.4817 Y9.3225 -G1 X3.4393 Y9.3535 F10 -G2 X3.4164 Y9.339 I-0.1249 J0.1719 F10 -G2 X3.3305 Y9.194 I-0.2108 J0.027 -G1 X3.2553 Y9.1394 -G1 X3.284 Y9.0509 -G2 X3.2857 Y9.0454 I-0.2021 J-0.0656 -G1 X3.3124 Y9.1277 -G2 X3.7175 Y9.1249 I0.2021 J-0.0656 -G1 X3.7427 Y9.0433 -G2 X3.7451 Y9.051 I0.2044 J-0.0581 -G1 X3.7738 Y9.1394 -G1 X3.6986 Y9.194 -G2 X3.6128 Y9.3389 I0.1249 J0.1719 -G2 X3.5897 Y9.3535 I0.1019 J0.1865 -G1 X3.5145 Y9.4082 -G1 X3.4393 Y9.3535 -G1 X3.4099 Y9.3939 F10 -G2 X3.368 Y9.372 I-0.0955 J0.1315 F10 -G2 X3.3681 Y9.366 I-0.1624 J-0.0061 -G2 X3.3011 Y9.2345 I-0.1625 J0 -G1 X3.1965 Y9.1585 -G1 X3.2364 Y9.0354 -G2 X3.2443 Y8.9893 I-0.1546 J-0.0502 -G1 X3.32 Y8.9893 -G1 X3.36 Y9.1123 -G2 X3.6698 Y9.1101 I0.1546 J-0.0502 -G1 X3.7071 Y8.9893 -G1 X3.7847 Y8.9893 -G2 X3.7926 Y9.0355 I0.1625 J-0.004 -G1 X3.8326 Y9.1585 -G1 X3.728 Y9.2345 -G2 X3.661 Y9.366 I0.0955 J0.1315 -G2 X3.6612 Y9.372 I0.1625 J0 -G2 X3.6191 Y9.3939 I0.0535 J0.1534 -G1 X3.5145 Y9.47 -G1 X3.4099 Y9.3939 -G1 X3.3805 Y9.4344 F10 -G2 X3.3078 Y9.4131 I-0.0661 J0.091 F10 -G2 X3.3181 Y9.366 I-0.1021 J-0.0471 -G2 X3.2718 Y9.2749 I-0.1125 J0 -G1 X3.1377 Y9.1776 -G1 X3.1889 Y9.02 -G2 X3.1944 Y8.9853 I-0.107 J-0.0347 -G2 X3.1845 Y8.9391 I-0.1125 J0 -G2 X3.1908 Y8.9393 I0.0063 J-0.1123 -G1 X3.3564 Y8.9393 -G1 X3.4075 Y9.0968 -G2 X3.622 Y9.0953 I0.107 J-0.0347 -G1 X3.6703 Y8.9393 -G1 X3.8384 Y8.9393 -G2 X3.8446 Y8.9391 I0 J-0.1125 -G2 X3.8347 Y8.9853 I0.1026 J0.0461 -G2 X3.8402 Y9.0201 I0.1125 J0 -G1 X3.8914 Y9.1776 -G1 X3.7574 Y9.2749 -G2 X3.711 Y9.366 I0.0661 J0.091 -G2 X3.7214 Y9.4131 I0.1125 J0 -G2 X3.6485 Y9.4344 I-0.0067 J0.1123 -G1 X3.5145 Y9.5318 -G1 X3.3805 Y9.4344 -G0 Z0.25 -G0 X6.013 Y7.1663 -G1 Z-0.05 F30 -G2 X6.0786 Y7.1663 I0.0328 J-0.2604 F10 -G1 X6.0458 Y7.1901 -G1 X6.013 Y7.1663 -G1 X5.9705 Y7.1972 F10 -G2 X5.9477 Y7.1828 I-0.1249 J0.1719 F10 -G2 X5.8618 Y7.0378 I-0.2108 J0.027 -G1 X5.7865 Y6.9831 -G1 X5.8152 Y6.8946 -G2 X5.8169 Y6.8892 I-0.2021 J-0.0656 -G1 X5.8436 Y6.9714 -G2 X6.2488 Y6.9686 I0.2021 J-0.0656 -G1 X6.274 Y6.8871 -G2 X6.2763 Y6.8947 I0.2044 J-0.0581 -G1 X6.3051 Y6.9832 -G1 X6.2299 Y7.0378 -G2 X6.144 Y7.1827 I0.1249 J0.1719 -G2 X6.121 Y7.1972 I0.1019 J0.1865 -G1 X6.0458 Y7.2519 -G1 X5.9705 Y7.1972 -G1 X5.9411 Y7.2377 F10 -G2 X5.8993 Y7.2158 I-0.0955 J0.1315 F10 -G2 X5.8994 Y7.2097 I-0.1624 J-0.0061 -G2 X5.8324 Y7.0782 I-0.1625 J0 -G1 X5.7277 Y7.0022 -G1 X5.7677 Y6.8792 -G2 X5.7756 Y6.833 I-0.1546 J-0.0502 -G1 X5.8513 Y6.833 -G1 X5.8912 Y6.956 -G2 X6.201 Y6.9538 I0.1546 J-0.0502 -G1 X6.2384 Y6.833 -G1 X6.316 Y6.833 -G2 X6.3239 Y6.8793 I0.1625 J-0.004 -G1 X6.3639 Y7.0023 -G1 X6.2593 Y7.0782 -G2 X6.1923 Y7.2097 I0.0955 J0.1315 -G2 X6.1924 Y7.2157 I0.1625 J0 -G2 X6.1504 Y7.2377 I0.0535 J0.1534 -G1 X6.0458 Y7.3137 -G1 X5.9411 Y7.2377 -G1 X5.9118 Y7.2781 F10 -G2 X5.839 Y7.2569 I-0.0661 J0.091 F10 -G2 X5.8494 Y7.2097 I-0.1021 J-0.0471 -G2 X5.803 Y7.1187 I-0.1125 J0 -G1 X5.669 Y7.0213 -G1 X5.7201 Y6.8638 -G2 X5.7256 Y6.829 I-0.107 J-0.0347 -G2 X5.7157 Y6.7829 I-0.1125 J0 -G2 X5.722 Y6.783 I0.0063 J-0.1123 -G1 X5.8876 Y6.783 -G1 X5.9388 Y6.9406 -G2 X6.1532 Y6.9391 I0.107 J-0.0347 -G1 X6.2015 Y6.783 -G1 X6.3697 Y6.783 -G2 X6.3758 Y6.7829 I0 J-0.1125 -G2 X6.3659 Y6.829 I0.1026 J0.0461 -G2 X6.3714 Y6.8638 I0.1125 J0 -G1 X6.4227 Y7.0213 -G1 X6.2887 Y7.1187 -G2 X6.2423 Y7.2097 I0.0661 J0.091 -G2 X6.2526 Y7.2569 I0.1125 J0 -G2 X6.1798 Y7.2781 I-0.0067 J0.1123 -G1 X6.0458 Y7.3755 -G1 X5.9118 Y7.2781 -G0 Z0.25 -G0 X6.015 Y6.0885 -G1 Z-0.05 F30 -G2 X6.0765 Y6.0885 I0.0307 J-0.2607 F10 -G1 X6.0458 Y6.1108 -G1 X6.015 Y6.0885 -G1 X5.9705 Y6.1179 F10 -G2 X5.9475 Y6.1034 I-0.1249 J0.1719 F10 -G2 X5.8618 Y5.9596 I-0.2106 J0.0282 -G1 X5.7865 Y5.9049 -G1 X5.8152 Y5.8164 -G2 X5.8169 Y5.811 I-0.2021 J-0.0656 -G1 X5.8436 Y5.8934 -G2 X6.2488 Y5.8906 I0.2021 J-0.0656 -G1 X6.274 Y5.809 -G2 X6.2763 Y5.8166 I0.2044 J-0.0581 -G1 X6.3051 Y5.905 -G1 X6.2299 Y5.9596 -G2 X6.1442 Y6.1033 I0.1249 J0.1719 -G2 X6.121 Y6.1179 I0.1017 J0.1866 -G1 X6.0458 Y6.1726 -G1 X5.9705 Y6.1179 -G1 X5.9411 Y6.1584 F10 -G2 X5.8993 Y6.1365 I-0.0955 J0.1315 F10 -G2 X5.8994 Y6.1315 I-0.1624 J-0.005 -G2 X5.8324 Y6.0001 I-0.1625 J0 -G1 X5.7277 Y5.924 -G1 X5.7677 Y5.801 -G2 X5.7756 Y5.755 I-0.1546 J-0.0502 -G1 X5.8513 Y5.755 -G1 X5.8912 Y5.8779 -G2 X6.201 Y5.8758 I0.1546 J-0.0502 -G1 X6.2384 Y5.755 -G1 X6.316 Y5.755 -G2 X6.3239 Y5.8011 I0.1624 J-0.0042 -G1 X6.3639 Y5.9241 -G1 X6.2593 Y6.0001 -G2 X6.1923 Y6.1315 I0.0955 J0.1315 -G2 X6.1924 Y6.1364 I0.1625 J0 -G2 X6.1504 Y6.1584 I0.0535 J0.1534 -G1 X6.0458 Y6.2344 -G1 X5.9411 Y6.1584 -G1 X5.9118 Y6.1988 F10 -G2 X5.8395 Y6.1775 I-0.0661 J0.091 F10 -G2 X5.8494 Y6.1315 I-0.1027 J-0.046 -G2 X5.803 Y6.0405 I-0.1125 J0 -G1 X5.669 Y5.9431 -G1 X5.7201 Y5.7856 -G2 X5.7256 Y5.7508 I-0.107 J-0.0347 -G2 X5.7158 Y5.7048 I-0.1125 J0 -G2 X5.722 Y5.705 I0.0062 J-0.1123 -G1 X5.8876 Y5.705 -G1 X5.9388 Y5.8625 -G2 X6.1532 Y5.861 I0.107 J-0.0347 -G1 X6.2015 Y5.705 -G1 X6.3697 Y5.705 -G2 X6.3757 Y5.7048 I0 J-0.1125 -G2 X6.3659 Y5.7508 I0.1027 J0.046 -G2 X6.3714 Y5.7856 I0.1125 J0 -G1 X6.4227 Y5.9431 -G1 X6.2887 Y6.0405 -G2 X6.2423 Y6.1315 I0.0661 J0.091 -G2 X6.2521 Y6.1775 I0.1125 J0 -G2 X6.1798 Y6.1988 I-0.0062 J0.1123 -G1 X6.0458 Y6.2962 -G1 X5.9118 Y6.1988 -G0 Z0.25 -G0 X6.6476 Y8.7837 -G1 Z-0.05 F30 -G2 X6.7097 Y8.7837 I0.031 J-0.2607 F10 -G1 X6.6786 Y8.8063 -G1 X6.6476 Y8.7837 -G1 X6.6033 Y8.8134 F10 -G2 X6.5803 Y8.7988 I-0.1249 J0.1719 F10 -G2 X6.4946 Y8.6549 I-0.2106 J0.028 -G1 X6.4193 Y8.6002 -G1 X6.448 Y8.5117 -G2 X6.4497 Y8.5063 I-0.2021 J-0.0656 -G1 X6.4764 Y8.5887 -G2 X6.8816 Y8.5858 I0.2021 J-0.0656 -G1 X6.9069 Y8.504 -G2 X6.9092 Y8.5117 I0.2045 J-0.0579 -G1 X6.9379 Y8.6002 -G1 X6.8627 Y8.6549 -G2 X6.7769 Y8.7988 I0.1249 J0.1719 -G2 X6.754 Y8.8133 I0.1019 J0.1865 -G1 X6.6786 Y8.868 -G1 X6.6033 Y8.8134 -G1 X6.5739 Y8.8538 F10 -G2 X6.5321 Y8.8319 I-0.0955 J0.1315 F10 -G2 X6.5322 Y8.8268 I-0.1624 J-0.0051 -G2 X6.4652 Y8.6953 I-0.1625 J0 -G1 X6.3605 Y8.6193 -G1 X6.4005 Y8.4963 -G2 X6.4083 Y8.4503 I-0.1546 J-0.0502 -G1 X6.4841 Y8.4503 -G1 X6.524 Y8.5732 -G2 X6.8338 Y8.5711 I0.1546 J-0.0502 -G1 X6.8712 Y8.4503 -G1 X6.9489 Y8.4503 -G2 X6.9568 Y8.4963 I0.1624 J-0.0042 -G1 X6.9967 Y8.6193 -G1 X6.8921 Y8.6953 -G2 X6.8251 Y8.8268 I0.0955 J0.1315 -G2 X6.8251 Y8.8319 I0.1625 J0 -G2 X6.7833 Y8.8538 I0.0537 J0.1534 -G1 X6.6786 Y8.9298 -G1 X6.5739 Y8.8538 -G1 X6.5445 Y8.8943 F10 -G2 X6.4723 Y8.8729 I-0.0661 J0.091 F10 -G2 X6.4822 Y8.8268 I-0.1026 J-0.0461 -G2 X6.4358 Y8.7358 I-0.1125 J0 -G1 X6.3017 Y8.6384 -G1 X6.3529 Y8.4808 -G2 X6.3584 Y8.4461 I-0.107 J-0.0347 -G2 X6.3486 Y8.4001 I-0.1125 J0 -G2 X6.3548 Y8.4003 I0.0062 J-0.1123 -G1 X6.5204 Y8.4003 -G1 X6.5715 Y8.5578 -G2 X6.786 Y8.5563 I0.107 J-0.0347 -G1 X6.8343 Y8.4003 -G1 X7.0024 Y8.4003 -G2 X7.0087 Y8.4001 I0 J-0.1125 -G2 X6.9988 Y8.4461 I0.1027 J0.046 -G2 X7.0043 Y8.4808 I0.1125 J0 -G1 X7.0555 Y8.6384 -G1 X6.9214 Y8.7358 -G2 X6.8751 Y8.8268 I0.0661 J0.091 -G2 X6.885 Y8.8729 I0.1125 J0 -G2 X6.8127 Y8.8942 I-0.0061 J0.1123 -G1 X6.6786 Y8.9916 -G1 X6.5445 Y8.8943 -G0 Z0.25 -G0 X4.1163 Y6.6275 -G1 Z-0.05 F30 -G2 X4.1784 Y6.6274 I0.031 J-0.2607 F10 -G1 X4.1473 Y6.65 -G1 X4.1163 Y6.6275 -G1 X4.0721 Y6.6571 F10 -G2 X4.049 Y6.6425 I-0.1249 J0.1719 F10 -G2 X3.9633 Y6.4986 I-0.2106 J0.028 -G1 X3.888 Y6.4439 -G1 X3.9168 Y6.3555 -G2 X3.9184 Y6.3501 I-0.2021 J-0.0656 -G1 X3.9452 Y6.4324 -G2 X4.3503 Y6.4296 I0.2021 J-0.0656 -G1 X4.3756 Y6.3478 -G2 X4.378 Y6.3555 I0.2045 J-0.0579 -G1 X4.4067 Y6.4439 -G1 X4.3314 Y6.4986 -G2 X4.2457 Y6.6425 I0.1249 J0.1719 -G2 X4.2227 Y6.6571 I0.1019 J0.1865 -G1 X4.1473 Y6.7118 -G1 X4.0721 Y6.6571 -G1 X4.0427 Y6.6976 F10 -G2 X4.0008 Y6.6756 I-0.0955 J0.1315 F10 -G2 X4.0009 Y6.6705 I-0.1624 J-0.0051 -G2 X3.9339 Y6.5391 I-0.1625 J0 -G1 X3.8293 Y6.463 -G1 X3.8692 Y6.34 -G2 X3.8771 Y6.294 I-0.1546 J-0.0502 -G1 X3.9528 Y6.294 -G1 X3.9927 Y6.417 -G2 X4.3025 Y6.4148 I0.1546 J-0.0502 -G1 X4.3399 Y6.294 -G1 X4.4176 Y6.294 -G2 X4.4255 Y6.34 I0.1624 J-0.0042 -G1 X4.4655 Y6.463 -G1 X4.3608 Y6.5391 -G2 X4.2938 Y6.6705 I0.0955 J0.1315 -G2 X4.2939 Y6.6756 I0.1625 J0 -G2 X4.2521 Y6.6975 I0.0537 J0.1534 -G1 X4.1473 Y6.7736 -G1 X4.0427 Y6.6976 -G1 X4.0133 Y6.738 F10 -G2 X3.941 Y6.7167 I-0.0661 J0.091 F10 -G2 X3.9509 Y6.6705 I-0.1026 J-0.0461 -G2 X3.9045 Y6.5795 I-0.1125 J0 -G1 X3.7705 Y6.4821 -G1 X3.8217 Y6.3246 -G2 X3.8272 Y6.2899 I-0.107 J-0.0347 -G2 X3.8173 Y6.2438 I-0.1125 J0 -G2 X3.8235 Y6.244 I0.0062 J-0.1123 -G1 X3.9891 Y6.244 -G1 X4.0403 Y6.4015 -G2 X4.2548 Y6.4 I0.107 J-0.0347 -G1 X4.303 Y6.244 -G1 X4.4712 Y6.244 -G2 X4.4774 Y6.2438 I0 J-0.1125 -G2 X4.4676 Y6.2899 I0.1027 J0.046 -G2 X4.4731 Y6.3246 I0.1125 J0 -G1 X4.5242 Y6.4821 -G1 X4.3902 Y6.5795 -G2 X4.3438 Y6.6705 I0.0661 J0.091 -G2 X4.3537 Y6.7167 I0.1125 J0 -G2 X4.2815 Y6.738 I-0.0061 J0.1123 -G1 X4.1473 Y6.8354 -G1 X4.0133 Y6.738 -G0 Z0.25 -G0 X3.4838 Y6.0885 -G1 Z-0.05 F30 -G2 X3.5453 Y6.0885 I0.0307 J-0.2607 F10 -G1 X3.5145 Y6.1108 -G1 X3.4838 Y6.0885 -G1 X3.4393 Y6.1179 F10 -G2 X3.4163 Y6.1034 I-0.1249 J0.1719 F10 -G2 X3.3305 Y5.9596 I-0.2106 J0.0282 -G1 X3.2553 Y5.9049 -G1 X3.284 Y5.8164 -G2 X3.2857 Y5.811 I-0.2021 J-0.0656 -G1 X3.3124 Y5.8934 -G2 X3.7175 Y5.8906 I0.2021 J-0.0656 -G1 X3.7428 Y5.809 -G2 X3.7451 Y5.8166 I0.2044 J-0.0581 -G1 X3.7738 Y5.905 -G1 X3.6986 Y5.9596 -G2 X3.6129 Y6.1033 I0.1249 J0.1719 -G2 X3.5897 Y6.1179 I0.1017 J0.1866 -G1 X3.5145 Y6.1726 -G1 X3.4393 Y6.1179 -G1 X3.4099 Y6.1584 F10 -G2 X3.368 Y6.1365 I-0.0955 J0.1315 F10 -G2 X3.3681 Y6.1315 I-0.1624 J-0.005 -G2 X3.3011 Y6.0001 I-0.1625 J0 -G1 X3.1965 Y5.924 -G1 X3.2364 Y5.801 -G2 X3.2443 Y5.755 I-0.1546 J-0.0502 -G1 X3.32 Y5.755 -G1 X3.36 Y5.8779 -G2 X3.6698 Y5.8758 I0.1546 J-0.0502 -G1 X3.7071 Y5.755 -G1 X3.7847 Y5.755 -G2 X3.7926 Y5.8011 I0.1624 J-0.0042 -G1 X3.8326 Y5.9241 -G1 X3.728 Y6.0001 -G2 X3.661 Y6.1315 I0.0955 J0.1315 -G2 X3.6611 Y6.1364 I0.1625 J0 -G2 X3.6191 Y6.1584 I0.0535 J0.1534 -G1 X3.5145 Y6.2344 -G1 X3.4099 Y6.1584 -G1 X3.3805 Y6.1988 F10 -G2 X3.3083 Y6.1775 I-0.0661 J0.091 F10 -G2 X3.3181 Y6.1315 I-0.1027 J-0.046 -G2 X3.2718 Y6.0405 I-0.1125 J0 -G1 X3.1377 Y5.9431 -G1 X3.1889 Y5.7856 -G2 X3.1944 Y5.7508 I-0.107 J-0.0347 -G2 X3.1845 Y5.7048 I-0.1125 J0 -G2 X3.1908 Y5.705 I0.0062 J-0.1123 -G1 X3.3564 Y5.705 -G1 X3.4075 Y5.8625 -G2 X3.622 Y5.861 I0.107 J-0.0347 -G1 X3.6703 Y5.705 -G1 X3.8384 Y5.705 -G2 X3.8445 Y5.7048 I0 J-0.1125 -G2 X3.8347 Y5.7508 I0.1027 J0.046 -G2 X3.8402 Y5.7856 I0.1125 J0 -G1 X3.8914 Y5.9431 -G1 X3.7574 Y6.0405 -G2 X3.711 Y6.1315 I0.0661 J0.091 -G2 X3.7209 Y6.1775 I0.1125 J0 -G2 X3.6485 Y6.1988 I-0.0062 J0.1123 -G1 X3.5145 Y6.2962 -G1 X3.3805 Y6.1988 -G0 Z0.25 -G0 X3.4817 Y7.1663 -G1 Z-0.05 F30 -G2 X3.5473 Y7.1663 I0.0328 J-0.2604 F10 -G1 X3.5145 Y7.1901 -G1 X3.4817 Y7.1663 -G1 X3.4393 Y7.1972 F10 -G2 X3.4164 Y7.1828 I-0.1249 J0.1719 F10 -G2 X3.3305 Y7.0378 I-0.2108 J0.027 -G1 X3.2553 Y6.9831 -G1 X3.284 Y6.8946 -G2 X3.2857 Y6.8892 I-0.2021 J-0.0656 -G1 X3.3124 Y6.9714 -G2 X3.7175 Y6.9686 I0.2021 J-0.0656 -G1 X3.7427 Y6.8871 -G2 X3.7451 Y6.8947 I0.2044 J-0.0581 -G1 X3.7738 Y6.9832 -G1 X3.6986 Y7.0378 -G2 X3.6128 Y7.1827 I0.1249 J0.1719 -G2 X3.5897 Y7.1972 I0.1019 J0.1865 -G1 X3.5145 Y7.2519 -G1 X3.4393 Y7.1972 -G1 X3.4099 Y7.2377 F10 -G2 X3.368 Y7.2158 I-0.0955 J0.1315 F10 -G2 X3.3681 Y7.2097 I-0.1624 J-0.0061 -G2 X3.3011 Y7.0782 I-0.1625 J0 -G1 X3.1965 Y7.0022 -G1 X3.2364 Y6.8792 -G2 X3.2443 Y6.833 I-0.1546 J-0.0502 -G1 X3.32 Y6.833 -G1 X3.36 Y6.956 -G2 X3.6698 Y6.9538 I0.1546 J-0.0502 -G1 X3.7071 Y6.833 -G1 X3.7847 Y6.833 -G2 X3.7926 Y6.8793 I0.1625 J-0.004 -G1 X3.8326 Y7.0023 -G1 X3.728 Y7.0782 -G2 X3.661 Y7.2097 I0.0955 J0.1315 -G2 X3.6612 Y7.2157 I0.1625 J0 -G2 X3.6191 Y7.2377 I0.0535 J0.1534 -G1 X3.5145 Y7.3137 -G1 X3.4099 Y7.2377 -G1 X3.3805 Y7.2781 F10 -G2 X3.3078 Y7.2569 I-0.0661 J0.091 F10 -G2 X3.3181 Y7.2097 I-0.1021 J-0.0471 -G2 X3.2718 Y7.1187 I-0.1125 J0 -G1 X3.1377 Y7.0213 -G1 X3.1889 Y6.8638 -G2 X3.1944 Y6.829 I-0.107 J-0.0347 -G2 X3.1845 Y6.7829 I-0.1125 J0 -G2 X3.1908 Y6.783 I0.0063 J-0.1123 -G1 X3.3564 Y6.783 -G1 X3.4075 Y6.9406 -G2 X3.622 Y6.9391 I0.107 J-0.0347 -G1 X3.6703 Y6.783 -G1 X3.8384 Y6.783 -G2 X3.8446 Y6.7829 I0 J-0.1125 -G2 X3.8347 Y6.829 I0.1026 J0.0461 -G2 X3.8402 Y6.8638 I0.1125 J0 -G1 X3.8914 Y7.0213 -G1 X3.7574 Y7.1187 -G2 X3.711 Y7.2097 I0.0661 J0.091 -G2 X3.7214 Y7.2569 I0.1125 J0 -G2 X3.6485 Y7.2781 I-0.0067 J0.1123 -G1 X3.5145 Y7.3755 -G1 X3.3805 Y7.2781 -G0 Z0.25 -G0 X2.851 Y7.7057 -G1 Z-0.05 F30 -G2 X2.9125 Y7.7057 I0.0307 J-0.2607 F10 -G1 X2.8817 Y7.728 -G1 X2.851 Y7.7057 -G1 X2.8065 Y7.7352 F10 -G2 X2.7832 Y7.7204 I-0.1249 J0.1719 F10 -G2 X2.6976 Y7.5779 I-0.2105 J0.0294 -G1 X2.6224 Y7.5233 -G1 X2.6512 Y7.4349 -G2 X2.6531 Y7.4288 I-0.2021 J-0.0657 -G1 X2.6796 Y7.5106 -G2 X3.0847 Y7.5078 I0.2021 J-0.0656 -G1 X3.1098 Y7.4267 -G2 X3.1123 Y7.4349 I0.2046 J-0.0576 -G1 X3.1411 Y7.5233 -G1 X3.0659 Y7.5779 -G2 X2.9803 Y7.7204 I0.1249 J0.1719 -G2 X2.957 Y7.7352 I0.1016 J0.1867 -G1 X2.8817 Y7.7898 -G1 X2.8065 Y7.7352 -G1 X2.7771 Y7.7756 F10 -G2 X2.7352 Y7.7537 I-0.0955 J0.1315 F10 -G2 X2.7352 Y7.7499 I-0.1625 J-0.0038 -G2 X2.6682 Y7.6184 I-0.1625 J0 -G1 X2.5636 Y7.5424 -G1 X2.6036 Y7.4194 -G2 X2.6116 Y7.3722 I-0.1545 J-0.0503 -G1 X2.6873 Y7.3722 -G1 X2.7272 Y7.4952 -G2 X3.037 Y7.493 I0.1546 J-0.0502 -G1 X3.0743 Y7.3722 -G1 X3.1519 Y7.3722 -G2 X3.1598 Y7.4194 I0.1625 J-0.0031 -G1 X3.1998 Y7.5424 -G1 X3.0952 Y7.6184 -G2 X3.0283 Y7.7499 I0.0955 J0.1315 -G2 X3.0283 Y7.7537 I0.1625 J0 -G2 X2.9864 Y7.7756 I0.0536 J0.1534 -G1 X2.8817 Y7.8516 -G1 X2.7771 Y7.7756 -G1 X2.7477 Y7.8161 F10 -G2 X2.6759 Y7.7947 I-0.0661 J0.091 F10 -G2 X2.6852 Y7.7499 I-0.1032 J-0.0449 -G2 X2.6388 Y7.6588 I-0.1125 J0 -G1 X2.5048 Y7.5615 -G1 X2.5561 Y7.404 -G2 X2.5616 Y7.3692 I-0.107 J-0.0348 -G2 X2.5512 Y7.322 I-0.1125 J0 -G2 X2.5578 Y7.3222 I0.0066 J-0.1123 -G1 X2.7236 Y7.3222 -G1 X2.7747 Y7.4797 -G2 X2.9892 Y7.4782 I0.107 J-0.0347 -G1 X3.0375 Y7.3222 -G1 X3.2056 Y7.3222 -G2 X3.2122 Y7.322 I0 J-0.1125 -G2 X3.2019 Y7.3692 I0.1021 J0.0471 -G2 X3.2074 Y7.404 I0.1125 J0 -G1 X3.2586 Y7.5615 -G1 X3.1246 Y7.6588 -G2 X3.0783 Y7.7499 I0.0661 J0.091 -G2 X3.0876 Y7.7947 I0.1125 J0 -G2 X3.0157 Y7.8161 I-0.0057 J0.1124 -G1 X2.8817 Y7.9134 -G1 X2.7477 Y7.8161 -G0 Z0.25 -G0 X1.5853 Y7.7057 -G1 Z-0.05 F30 -G2 X1.6469 Y7.7057 I0.0307 J-0.2607 F10 -G1 X1.6161 Y7.7281 -G1 X1.5853 Y7.7057 -G1 X1.5408 Y7.7351 F10 -G2 X1.5176 Y7.7205 I-0.1249 J0.172 F10 -G2 X1.4321 Y7.5779 I-0.2105 J0.0294 -G1 X1.3568 Y7.5232 -G1 X1.3855 Y7.4348 -G2 X1.3874 Y7.4288 I-0.2021 J-0.0656 -G1 X1.4139 Y7.5106 -G2 X1.8191 Y7.5078 I0.2021 J-0.0656 -G1 X1.8442 Y7.4265 -G2 X1.8467 Y7.4348 I0.2046 J-0.0573 -G1 X1.8754 Y7.5232 -G1 X1.8002 Y7.5779 -G2 X1.7146 Y7.7205 I0.1249 J0.1719 -G2 X1.6914 Y7.7352 I0.1017 J0.1866 -G1 X1.6161 Y7.7899 -G1 X1.5408 Y7.7351 -G1 X1.5114 Y7.7756 F10 -G2 X1.4696 Y7.7537 I-0.0955 J0.1315 F10 -G2 X1.4697 Y7.7499 I-0.1625 J-0.0039 -G2 X1.4027 Y7.6184 I-0.1625 J0 -G1 X1.298 Y7.5424 -G1 X1.338 Y7.4193 -G2 X1.3459 Y7.3722 I-0.1546 J-0.0502 -G1 X1.4216 Y7.3722 -G1 X1.4615 Y7.4952 -G2 X1.7713 Y7.493 I0.1546 J-0.0502 -G1 X1.8087 Y7.3722 -G1 X1.8863 Y7.3722 -G2 X1.8943 Y7.4193 I0.1625 J-0.0031 -G1 X1.9342 Y7.5424 -G1 X1.8296 Y7.6184 -G2 X1.7626 Y7.7499 I0.0955 J0.1315 -G2 X1.7626 Y7.7537 I0.1625 J0 -G2 X1.7208 Y7.7756 I0.0537 J0.1534 -G1 X1.6161 Y7.8516 -G1 X1.5114 Y7.7756 -G1 X1.482 Y7.816 F10 -G2 X1.4103 Y7.7947 I-0.0661 J0.091 F10 -G2 X1.4197 Y7.7499 I-0.1032 J-0.0449 -G2 X1.3733 Y7.6588 I-0.1125 J0 -G1 X1.2392 Y7.5615 -G1 X1.2904 Y7.4039 -G2 X1.2959 Y7.3692 I-0.107 J-0.0347 -G2 X1.2855 Y7.322 I-0.1125 J0 -G2 X1.2923 Y7.3222 I0.0067 J-0.1123 -G1 X1.4579 Y7.3222 -G1 X1.509 Y7.4797 -G2 X1.7235 Y7.4782 I0.107 J-0.0347 -G1 X1.7718 Y7.3222 -G1 X1.9399 Y7.3222 -G2 X1.9467 Y7.322 I0 J-0.1125 -G2 X1.9363 Y7.3692 I0.1021 J0.0471 -G2 X1.9418 Y7.4039 I0.1125 J0 -G1 X1.993 Y7.5615 -G1 X1.8589 Y7.6588 -G2 X1.8126 Y7.7499 I0.0661 J0.091 -G2 X1.8219 Y7.7947 I0.1125 J0 -G2 X1.7502 Y7.8161 I-0.0056 J0.1124 -G1 X1.6162 Y7.9134 -G1 X1.482 Y7.816 -G0 Z0.25 -G0 X2.8508 Y8.7837 -G1 Z-0.05 F30 -G2 X2.9127 Y8.7837 I0.031 J-0.2607 F10 -G1 X2.8817 Y8.8062 -G1 X2.8508 Y8.7837 -G1 X2.8065 Y8.8134 F10 -G2 X2.7833 Y8.7987 I-0.1249 J0.1719 F10 -G2 X2.6976 Y8.6549 I-0.2106 J0.0281 -G1 X2.6224 Y8.6002 -G1 X2.6512 Y8.5118 -G2 X2.6529 Y8.5063 I-0.2021 J-0.0657 -G1 X2.6796 Y8.5887 -G2 X3.0847 Y8.5858 I0.2021 J-0.0656 -G1 X3.11 Y8.5042 -G2 X3.1123 Y8.5118 I0.2044 J-0.0581 -G1 X3.1411 Y8.6002 -G1 X3.0659 Y8.6549 -G2 X2.9801 Y8.7987 I0.1249 J0.1719 -G2 X2.957 Y8.8134 I0.1017 J0.1866 -G1 X2.8817 Y8.868 -G1 X2.8065 Y8.8134 -G1 X2.7771 Y8.8538 F10 -G2 X2.7351 Y8.8318 I-0.0955 J0.1315 F10 -G2 X2.7352 Y8.8268 I-0.1624 J-0.005 -G2 X2.6682 Y8.6953 I-0.1625 J0 -G1 X2.5636 Y8.6193 -G1 X2.6036 Y8.4964 -G2 X2.6115 Y8.4503 I-0.1545 J-0.0503 -G1 X2.6873 Y8.4503 -G1 X2.7272 Y8.5732 -G2 X3.037 Y8.5711 I0.1546 J-0.0502 -G1 X3.0743 Y8.4503 -G1 X3.1519 Y8.4503 -G2 X3.1598 Y8.4964 I0.1624 J-0.0042 -G1 X3.1998 Y8.6193 -G1 X3.0952 Y8.6953 -G2 X3.0283 Y8.8268 I0.0955 J0.1315 -G2 X3.0283 Y8.8318 I0.1625 J0 -G2 X2.9864 Y8.8538 I0.0535 J0.1534 -G1 X2.8817 Y8.9298 -G1 X2.7771 Y8.8538 -G1 X2.7477 Y8.8943 F10 -G2 X2.6753 Y8.8729 I-0.0661 J0.091 F10 -G2 X2.6852 Y8.8268 I-0.1026 J-0.0461 -G2 X2.6388 Y8.7358 I-0.1125 J0 -G1 X2.5048 Y8.6384 -G1 X2.5561 Y8.4809 -G2 X2.5616 Y8.4461 I-0.107 J-0.0348 -G2 X2.5518 Y8.4001 I-0.1125 J0 -G2 X2.5578 Y8.4003 I0.0061 J-0.1123 -G1 X2.7236 Y8.4003 -G1 X2.7747 Y8.5578 -G2 X2.9892 Y8.5563 I0.107 J-0.0347 -G1 X3.0375 Y8.4003 -G1 X3.2056 Y8.4003 -G2 X3.2117 Y8.4001 I0 J-0.1125 -G2 X3.2019 Y8.4461 I0.1027 J0.046 -G2 X3.2074 Y8.4809 I0.1125 J0 -G1 X3.2586 Y8.6384 -G1 X3.1246 Y8.7358 -G2 X3.0783 Y8.8268 I0.0661 J0.091 -G2 X3.0882 Y8.8729 I0.1125 J0 -G2 X3.0157 Y8.8943 I-0.0063 J0.1123 -G1 X2.8817 Y8.9916 -G1 X2.7477 Y8.8943 -G0 Z0.25 -G0 X4.1166 Y7.7057 -G1 Z-0.05 F30 -G2 X4.1782 Y7.7057 I0.0307 J-0.2607 F10 -G1 X4.1473 Y7.7281 -G1 X4.1166 Y7.7057 -G1 X4.0721 Y7.7352 F10 -G2 X4.0489 Y7.7205 I-0.1249 J0.1719 F10 -G2 X3.9633 Y7.5779 I-0.2105 J0.0294 -G1 X3.888 Y7.5232 -G1 X3.9168 Y7.4348 -G2 X3.9186 Y7.4288 I-0.2021 J-0.0656 -G1 X3.9452 Y7.5106 -G2 X4.3503 Y7.5078 I0.2021 J-0.0656 -G1 X4.3754 Y7.4265 -G2 X4.378 Y7.4348 I0.2046 J-0.0573 -G1 X4.4067 Y7.5232 -G1 X4.3314 Y7.5779 -G2 X4.2459 Y7.7205 I0.1249 J0.1719 -G2 X4.2227 Y7.7351 I0.1017 J0.1866 -G1 X4.1473 Y7.7899 -G1 X4.0721 Y7.7352 -G1 X4.0427 Y7.7756 F10 -G2 X4.0009 Y7.7537 I-0.0955 J0.1315 F10 -G2 X4.0009 Y7.7499 I-0.1625 J-0.0039 -G2 X3.9339 Y7.6184 I-0.1625 J0 -G1 X3.8293 Y7.5424 -G1 X3.8692 Y7.4193 -G2 X3.8771 Y7.3722 I-0.1546 J-0.0502 -G1 X3.9528 Y7.3722 -G1 X3.9927 Y7.4952 -G2 X4.3025 Y7.493 I0.1546 J-0.0502 -G1 X4.3399 Y7.3722 -G1 X4.4176 Y7.3722 -G2 X4.4255 Y7.4193 I0.1625 J-0.0031 -G1 X4.4655 Y7.5424 -G1 X4.3608 Y7.6184 -G2 X4.2938 Y7.7499 I0.0955 J0.1315 -G2 X4.2939 Y7.7537 I0.1625 J0 -G2 X4.2521 Y7.7756 I0.0537 J0.1534 -G1 X4.1473 Y7.8516 -G1 X4.0427 Y7.7756 -G1 X4.0133 Y7.8161 F10 -G2 X3.9416 Y7.7947 I-0.0661 J0.091 F10 -G2 X3.9509 Y7.7499 I-0.1032 J-0.0449 -G2 X3.9045 Y7.6588 I-0.1125 J0 -G1 X3.7705 Y7.5615 -G1 X3.8217 Y7.4039 -G2 X3.8272 Y7.3692 I-0.107 J-0.0347 -G2 X3.8168 Y7.322 I-0.1125 J0 -G2 X3.8235 Y7.3222 I0.0067 J-0.1123 -G1 X3.9891 Y7.3222 -G1 X4.0403 Y7.4797 -G2 X4.2548 Y7.4782 I0.107 J-0.0347 -G1 X4.303 Y7.3222 -G1 X4.4712 Y7.3222 -G2 X4.4779 Y7.322 I0 J-0.1125 -G2 X4.4676 Y7.3692 I0.1021 J0.0471 -G2 X4.4731 Y7.4039 I0.1125 J0 -G1 X4.5242 Y7.5615 -G1 X4.3902 Y7.6588 -G2 X4.3438 Y7.7499 I0.0661 J0.091 -G2 X4.3532 Y7.7947 I0.1125 J0 -G2 X4.2815 Y7.816 I-0.0056 J0.1124 -G1 X4.1473 Y7.9134 -G1 X4.0133 Y7.8161 -G0 Z0.25 -G0 X6.013 Y9.3225 -G1 Z-0.05 F30 -G2 X6.0786 Y9.3225 I0.0328 J-0.2604 F10 -G1 X6.0458 Y9.3464 -G1 X6.013 Y9.3225 -G1 X5.9705 Y9.3535 F10 -G2 X5.9477 Y9.339 I-0.1249 J0.1719 F10 -G2 X5.8618 Y9.194 I-0.2108 J0.027 -G1 X5.7865 Y9.1394 -G1 X5.8152 Y9.0509 -G2 X5.8169 Y9.0454 I-0.2021 J-0.0656 -G1 X5.8436 Y9.1277 -G2 X6.2488 Y9.1249 I0.2021 J-0.0656 -G1 X6.274 Y9.0433 -G2 X6.2763 Y9.051 I0.2044 J-0.0581 -G1 X6.3051 Y9.1394 -G1 X6.2299 Y9.194 -G2 X6.144 Y9.3389 I0.1249 J0.1719 -G2 X6.121 Y9.3535 I0.1019 J0.1865 -G1 X6.0458 Y9.4082 -G1 X5.9705 Y9.3535 -G1 X5.9411 Y9.3939 F10 -G2 X5.8993 Y9.372 I-0.0955 J0.1315 F10 -G2 X5.8994 Y9.366 I-0.1624 J-0.0061 -G2 X5.8324 Y9.2345 I-0.1625 J0 -G1 X5.7277 Y9.1585 -G1 X5.7677 Y9.0354 -G2 X5.7756 Y8.9893 I-0.1546 J-0.0502 -G1 X5.8513 Y8.9893 -G1 X5.8912 Y9.1123 -G2 X6.201 Y9.1101 I0.1546 J-0.0502 -G1 X6.2384 Y8.9893 -G1 X6.316 Y8.9893 -G2 X6.3239 Y9.0355 I0.1625 J-0.004 -G1 X6.3639 Y9.1585 -G1 X6.2593 Y9.2345 -G2 X6.1923 Y9.366 I0.0955 J0.1315 -G2 X6.1924 Y9.372 I0.1625 J0 -G2 X6.1504 Y9.3939 I0.0535 J0.1534 -G1 X6.0458 Y9.47 -G1 X5.9411 Y9.3939 -G1 X5.9118 Y9.4344 F10 -G2 X5.839 Y9.4131 I-0.0661 J0.091 F10 -G2 X5.8494 Y9.366 I-0.1021 J-0.0471 -G2 X5.803 Y9.2749 I-0.1125 J0 -G1 X5.669 Y9.1776 -G1 X5.7201 Y9.02 -G2 X5.7256 Y8.9853 I-0.107 J-0.0347 -G2 X5.7157 Y8.9391 I-0.1125 J0 -G2 X5.722 Y8.9393 I0.0063 J-0.1123 -G1 X5.8876 Y8.9393 -G1 X5.9388 Y9.0968 -G2 X6.1532 Y9.0953 I0.107 J-0.0347 -G1 X6.2015 Y8.9393 -G1 X6.3697 Y8.9393 -G2 X6.3758 Y8.9391 I0 J-0.1125 -G2 X6.3659 Y8.9853 I0.1026 J0.0461 -G2 X6.3714 Y9.0201 I0.1125 J0 -G1 X6.4227 Y9.1776 -G1 X6.2887 Y9.2749 -G2 X6.2423 Y9.366 I0.0661 J0.091 -G2 X6.2526 Y9.4131 I0.1125 J0 -G2 X6.1798 Y9.4344 I-0.0067 J0.1123 -G1 X6.0458 Y9.5318 -G1 X5.9118 Y9.4344 -G0 Z0.25 -G0 X2.8508 Y6.6275 -G1 Z-0.05 F30 -G2 X2.9127 Y6.6275 I0.031 J-0.2607 F10 -G1 X2.8817 Y6.65 -G1 X2.8508 Y6.6275 -G1 X2.8065 Y6.6571 F10 -G2 X2.7833 Y6.6425 I-0.1249 J0.1719 F10 -G2 X2.6976 Y6.4986 I-0.2106 J0.0281 -G1 X2.6224 Y6.444 -G1 X2.6512 Y6.3556 -G2 X2.6529 Y6.3501 I-0.2021 J-0.0657 -G1 X2.6796 Y6.4324 -G2 X3.0847 Y6.4296 I0.2021 J-0.0656 -G1 X3.11 Y6.348 -G2 X3.1123 Y6.3556 I0.2044 J-0.0581 -G1 X3.1411 Y6.444 -G1 X3.0659 Y6.4986 -G2 X2.9801 Y6.6425 I0.1249 J0.1719 -G2 X2.957 Y6.6571 I0.1017 J0.1866 -G1 X2.8817 Y6.7118 -G1 X2.8065 Y6.6571 -G1 X2.7771 Y6.6976 F10 -G2 X2.7351 Y6.6756 I-0.0955 J0.1315 F10 -G2 X2.7352 Y6.6705 I-0.1624 J-0.005 -G2 X2.6682 Y6.5391 I-0.1625 J0 -G1 X2.5636 Y6.4631 -G1 X2.6036 Y6.3401 -G2 X2.6115 Y6.294 I-0.1545 J-0.0503 -G1 X2.6873 Y6.294 -G1 X2.7272 Y6.417 -G2 X3.037 Y6.4148 I0.1546 J-0.0502 -G1 X3.0743 Y6.294 -G1 X3.1519 Y6.294 -G2 X3.1598 Y6.3401 I0.1624 J-0.0042 -G1 X3.1998 Y6.4631 -G1 X3.0952 Y6.5391 -G2 X3.0283 Y6.6705 I0.0955 J0.1315 -G2 X3.0283 Y6.6756 I0.1625 J0 -G2 X2.9864 Y6.6976 I0.0535 J0.1534 -G1 X2.8817 Y6.7736 -G1 X2.7771 Y6.6976 -G1 X2.7477 Y6.738 F10 -G2 X2.6753 Y6.7167 I-0.0661 J0.091 F10 -G2 X2.6852 Y6.6705 I-0.1026 J-0.0461 -G2 X2.6388 Y6.5795 I-0.1125 J0 -G1 X2.5048 Y6.4822 -G1 X2.5561 Y6.3246 -G2 X2.5616 Y6.2899 I-0.107 J-0.0348 -G2 X2.5518 Y6.2439 I-0.1125 J0 -G2 X2.5578 Y6.244 I0.0061 J-0.1123 -G1 X2.7236 Y6.244 -G1 X2.7747 Y6.4015 -G2 X2.9892 Y6.4 I0.107 J-0.0347 -G1 X3.0375 Y6.244 -G1 X3.2056 Y6.244 -G2 X3.2117 Y6.2439 I0 J-0.1125 -G2 X3.2019 Y6.2899 I0.1027 J0.046 -G2 X3.2074 Y6.3246 I0.1125 J0 -G1 X3.2586 Y6.4822 -G1 X3.1246 Y6.5795 -G2 X3.0783 Y6.6705 I0.0661 J0.091 -G2 X3.0882 Y6.7167 I0.1125 J0 -G2 X3.0157 Y6.738 I-0.0063 J0.1123 -G1 X2.8817 Y6.8354 -G1 X2.7477 Y6.738 -G0 Z0.25 -G0 X5.3822 Y7.7057 -G1 Z-0.05 F30 -G2 X5.4437 Y7.7057 I0.0307 J-0.2607 F10 -G1 X5.413 Y7.728 -G1 X5.3822 Y7.7057 -G1 X5.3378 Y7.7352 F10 -G2 X5.3144 Y7.7204 I-0.1249 J0.1719 F10 -G2 X5.2289 Y7.5779 I-0.2105 J0.0294 -G1 X5.1537 Y7.5233 -G1 X5.1824 Y7.4349 -G2 X5.1843 Y7.4288 I-0.2021 J-0.0657 -G1 X5.2109 Y7.5106 -G2 X5.616 Y7.5078 I0.2021 J-0.0656 -G1 X5.6411 Y7.4267 -G2 X5.6435 Y7.4349 I0.2046 J-0.0576 -G1 X5.6723 Y7.5233 -G1 X5.5971 Y7.5779 -G2 X5.5116 Y7.7204 I0.1249 J0.1719 -G2 X5.4882 Y7.7352 I0.1016 J0.1867 -G1 X5.413 Y7.7898 -G1 X5.3378 Y7.7352 -G1 X5.3084 Y7.7756 F10 -G2 X5.2664 Y7.7537 I-0.0955 J0.1315 F10 -G2 X5.2665 Y7.7499 I-0.1625 J-0.0038 -G2 X5.1995 Y7.6184 I-0.1625 J0 -G1 X5.0949 Y7.5424 -G1 X5.1349 Y7.4194 -G2 X5.1428 Y7.3722 I-0.1545 J-0.0503 -G1 X5.2185 Y7.3722 -G1 X5.2584 Y7.4952 -G2 X5.5682 Y7.493 I0.1546 J-0.0502 -G1 X5.6056 Y7.3722 -G1 X5.6832 Y7.3722 -G2 X5.6911 Y7.4194 I0.1625 J-0.0031 -G1 X5.7311 Y7.5424 -G1 X5.6265 Y7.6184 -G2 X5.5595 Y7.7499 I0.0955 J0.1315 -G2 X5.5596 Y7.7537 I0.1625 J0 -G2 X5.5176 Y7.7756 I0.0536 J0.1534 -G1 X5.413 Y7.8516 -G1 X5.3084 Y7.7756 -G1 X5.279 Y7.8161 F10 -G2 X5.2071 Y7.7947 I-0.0661 J0.091 F10 -G2 X5.2165 Y7.7499 I-0.1032 J-0.0449 -G2 X5.1701 Y7.6588 I-0.1125 J0 -G1 X5.0361 Y7.5615 -G1 X5.0873 Y7.404 -G2 X5.0928 Y7.3692 I-0.107 J-0.0348 -G2 X5.0825 Y7.322 I-0.1125 J0 -G2 X5.0891 Y7.3222 I0.0066 J-0.1123 -G1 X5.2548 Y7.3222 -G1 X5.306 Y7.4797 -G2 X5.5205 Y7.4782 I0.107 J-0.0347 -G1 X5.5687 Y7.3222 -G1 X5.7369 Y7.3222 -G2 X5.7435 Y7.322 I0 J-0.1125 -G2 X5.7331 Y7.3692 I0.1021 J0.0471 -G2 X5.7386 Y7.404 I0.1125 J0 -G1 X5.7899 Y7.5615 -G1 X5.6559 Y7.6588 -G2 X5.6095 Y7.7499 I0.0661 J0.091 -G2 X5.6188 Y7.7947 I0.1125 J0 -G2 X5.547 Y7.8161 I-0.0057 J0.1124 -G1 X5.413 Y7.9134 -G1 X5.279 Y7.8161 -G0 Z0.25 -G0 X4.9436 Y9.4748 -G1 Z-0.05 F30 -G1 X4.7802 Y9.5936 F10 -G1 X4.6168 Y9.4748 -G2 X4.5176 Y9.5254 I-0.0367 J0.0506 -G2 X4.5206 Y9.5447 I0.0625 J0 -G1 X4.583 Y9.7368 -G1 X4.4196 Y9.8555 -G2 X4.3938 Y9.9061 I0.0367 J0.0506 -G2 X4.4563 Y9.9686 I0.0625 J0 -G1 X4.6583 Y9.9686 -G1 X4.7208 Y10.1608 -G2 X4.7388 Y10.1883 I0.0594 J-0.0193 -G1 X3.5559 Y10.1883 -G2 X3.5742 Y10.16 I-0.0414 J-0.0468 -G1 X3.6334 Y9.9686 -G1 X3.8384 Y9.9686 -G2 X3.9009 Y9.9061 I0 J-0.0625 -G2 X3.8751 Y9.8555 I-0.0625 J0 -G1 X3.7117 Y9.7368 -G1 X3.7741 Y9.5447 -G2 X3.7772 Y9.5254 I-0.0594 J-0.0193 -G2 X3.6779 Y9.4748 I-0.0625 J0 -G1 X3.5145 Y9.5936 -G1 X3.3511 Y9.4748 -G2 X3.2519 Y9.5254 I-0.0367 J0.0506 -G2 X3.2549 Y9.5447 I0.0625 J0 -G1 X3.3174 Y9.7368 -G1 X3.154 Y9.8555 -G2 X3.1283 Y9.9061 I0.0367 J0.0506 -G2 X3.1908 Y9.9686 I0.0625 J0 -G1 X3.3927 Y9.9686 -G1 X3.4551 Y10.1608 -G2 X3.4731 Y10.1883 I0.0594 J-0.0193 -G1 X2.2904 Y10.1883 -G2 X2.3087 Y10.1599 I-0.0414 J-0.0468 -G1 X2.3677 Y9.9686 -G1 X2.5727 Y9.9686 -G2 X2.6352 Y9.9061 I0 J-0.0625 -G2 X2.6094 Y9.8555 I-0.0625 J0 -G1 X2.4461 Y9.7368 -G1 X2.5085 Y9.5447 -G2 X2.5116 Y9.5254 I-0.0594 J-0.0193 -G2 X2.4124 Y9.4748 I-0.0625 J0 -G1 X2.249 Y9.5936 -G1 X2.0856 Y9.4748 -G2 X1.9863 Y9.5254 I-0.0367 J0.0506 -G2 X1.9894 Y9.5447 I0.0625 J0 -G1 X2.0517 Y9.7368 -G1 X1.8883 Y9.8555 -G2 X1.8626 Y9.9061 I0.0367 J0.0506 -G2 X1.9251 Y9.9686 I0.0625 J0 -G1 X2.127 Y9.9686 -G1 X2.1895 Y10.1608 -G2 X2.2075 Y10.1883 I0.0594 J-0.0193 -G1 X1.0247 Y10.1883 -G2 X1.043 Y10.16 I-0.0414 J-0.0468 -G1 X1.1021 Y9.9686 -G1 X1.3072 Y9.9686 -G2 X1.3697 Y9.9061 I0 J-0.0625 -G2 X1.3439 Y9.8555 I-0.0625 J0 -G1 X1.1805 Y9.7368 -G1 X1.2428 Y9.5447 -G2 X1.2459 Y9.5254 I-0.0594 J-0.0193 -G2 X1.1467 Y9.4748 I-0.0625 J0 -G1 X0.9833 Y9.5936 -G1 X0.8199 Y9.4748 -G2 X0.7206 Y9.5254 I-0.0367 J0.0506 -G2 X0.7237 Y9.5447 I0.0625 J0 -G1 X0.7862 Y9.7368 -G1 X0.6228 Y9.8555 -G2 X0.597 Y9.9061 I0.0367 J0.0506 -G2 X0.6595 Y9.9686 I0.0625 J0 -G1 X0.8614 Y9.9686 -G1 X0.9238 Y10.1608 -G2 X0.9418 Y10.1883 I0.0594 J-0.0193 -G1 X0.538 Y10.1883 -G1 X0.538 Y5.1883 -G1 X0.7252 Y5.1883 -G2 X0.7206 Y5.2118 I0.0579 J0.0235 -G2 X0.7237 Y5.2311 I0.0625 J0 -G1 X0.7862 Y5.4232 -G1 X0.6228 Y5.5419 -G2 X0.597 Y5.5925 I0.0367 J0.0506 -G2 X0.6595 Y5.655 I0.0625 J0 -G1 X0.8615 Y5.655 -G1 X0.9238 Y5.8471 -G2 X1.043 Y5.8462 I0.0594 J-0.0193 -G1 X1.1021 Y5.655 -G1 X1.3072 Y5.655 -G2 X1.3697 Y5.5925 I0 J-0.0625 -G2 X1.3439 Y5.5419 I-0.0625 J0 -G1 X1.1805 Y5.4232 -G1 X1.2428 Y5.2311 -G2 X1.2459 Y5.2118 I-0.0594 J-0.0193 -G2 X1.2413 Y5.1883 I-0.0625 J0 -G1 X1.9909 Y5.1883 -G2 X1.9863 Y5.2118 I0.0579 J0.0235 -G2 X1.9894 Y5.2311 I0.0625 J0 -G1 X2.0517 Y5.4232 -G1 X1.8883 Y5.5419 -G2 X1.8626 Y5.5925 I0.0367 J0.0506 -G2 X1.9251 Y5.655 I0.0625 J0 -G1 X2.127 Y5.655 -G1 X2.1895 Y5.8471 -G2 X2.3087 Y5.8462 I0.0594 J-0.0193 -G1 X2.3677 Y5.655 -G1 X2.5727 Y5.655 -G2 X2.6352 Y5.5925 I0 J-0.0625 -G2 X2.6094 Y5.5419 I-0.0625 J0 -G1 X2.4461 Y5.4232 -G1 X2.5085 Y5.2311 -G2 X2.5116 Y5.2118 I-0.0594 J-0.0193 -G2 X2.507 Y5.1883 I-0.0625 J0 -G1 X3.2565 Y5.1883 -G2 X3.2519 Y5.2118 I0.0579 J0.0235 -G2 X3.2549 Y5.2311 I0.0625 J0 -G1 X3.3174 Y5.4232 -G1 X3.154 Y5.5419 -G2 X3.1283 Y5.5925 I0.0367 J0.0506 -G2 X3.1908 Y5.655 I0.0625 J0 -G1 X3.3927 Y5.655 -G1 X3.4551 Y5.8471 -G2 X3.5742 Y5.8462 I0.0594 J-0.0193 -G1 X3.6334 Y5.655 -G1 X3.8384 Y5.655 -G2 X3.9009 Y5.5925 I0 J-0.0625 -G2 X3.8751 Y5.5419 I-0.0625 J0 -G1 X3.7117 Y5.4232 -G1 X3.7741 Y5.2311 -G2 X3.7772 Y5.2118 I-0.0594 J-0.0193 -G2 X3.7726 Y5.1883 I-0.0625 J0 -G1 X4.5221 Y5.1883 -G2 X4.5176 Y5.2118 I0.0579 J0.0235 -G2 X4.5206 Y5.2311 I0.0625 J0 -G1 X4.583 Y5.4232 -G1 X4.4196 Y5.5419 -G2 X4.3938 Y5.5925 I0.0367 J0.0506 -G2 X4.4563 Y5.655 I0.0625 J0 -G1 X4.6583 Y5.655 -G1 X4.7208 Y5.8471 -G2 X4.8399 Y5.8462 I0.0594 J-0.0193 -G1 X4.899 Y5.655 -G1 X5.104 Y5.655 -G2 X5.1665 Y5.5925 I0 J-0.0625 -G2 X5.1407 Y5.5419 I-0.0625 J0 -G1 X4.9773 Y5.4232 -G1 X5.0398 Y5.2311 -G2 X5.0428 Y5.2118 I-0.0594 J-0.0193 -G2 X5.0383 Y5.1883 I-0.0625 J0 -G1 X5.7877 Y5.1883 -G2 X5.7831 Y5.2118 I0.0579 J0.0235 -G2 X5.7862 Y5.2311 I0.0625 J0 -G1 X5.8487 Y5.4232 -G1 X5.6853 Y5.5419 -G2 X5.6595 Y5.5925 I0.0367 J0.0506 -G2 X5.722 Y5.655 I0.0625 J0 -G1 X5.924 Y5.655 -G1 X5.9863 Y5.8471 -G2 X6.1055 Y5.8462 I0.0594 J-0.0193 -G1 X6.1646 Y5.655 -G1 X6.3697 Y5.655 -G2 X6.4322 Y5.5925 I0 J-0.0625 -G2 X6.4064 Y5.5419 I-0.0625 J0 -G1 X6.243 Y5.4232 -G1 X6.3053 Y5.2311 -G2 X6.3084 Y5.2118 I-0.0594 J-0.0193 -G2 X6.3038 Y5.1883 I-0.0625 J0 -G1 X7.0534 Y5.1883 -G2 X7.0488 Y5.2118 I0.0579 J0.0235 -G2 X7.0519 Y5.2311 I0.0625 J0 -G1 X7.1142 Y5.4232 -G1 X6.9508 Y5.5419 -G2 X6.9251 Y5.5925 I0.0367 J0.0506 -G2 X6.9876 Y5.655 I0.0625 J0 -G1 X7.1895 Y5.655 -G1 X7.252 Y5.8471 -G2 X7.3712 Y5.8462 I0.0594 J-0.0193 -G1 X7.4302 Y5.655 -G1 X7.6352 Y5.655 -G2 X7.6977 Y5.5925 I0 J-0.0625 -G2 X7.6719 Y5.5419 I-0.0625 J0 -G1 X7.5086 Y5.4232 -G1 X7.571 Y5.2311 -G2 X7.5741 Y5.2118 I-0.0594 J-0.0193 -G2 X7.5695 Y5.1883 I-0.0625 J0 -G1 X7.7567 Y5.1883 -G1 X7.7567 Y10.1883 -G1 X7.3529 Y10.1883 -G2 X7.3712 Y10.1599 I-0.0414 J-0.0468 -G1 X7.4302 Y9.9686 -G1 X7.6352 Y9.9686 -G2 X7.6977 Y9.9061 I0 J-0.0625 -G2 X7.6719 Y9.8555 I-0.0625 J0 -G1 X7.5086 Y9.7368 -G1 X7.571 Y9.5447 -G2 X7.5741 Y9.5254 I-0.0594 J-0.0193 -G2 X7.4749 Y9.4748 I-0.0625 J0 -G1 X7.3115 Y9.5936 -G1 X7.1481 Y9.4748 -G2 X7.0488 Y9.5254 I-0.0367 J0.0506 -G2 X7.0519 Y9.5447 I0.0625 J0 -G1 X7.1142 Y9.7368 -G1 X6.9508 Y9.8555 -G2 X6.9251 Y9.9061 I0.0367 J0.0506 -G2 X6.9876 Y9.9686 I0.0625 J0 -G1 X7.1895 Y9.9686 -G1 X7.252 Y10.1608 -G2 X7.27 Y10.1883 I0.0594 J-0.0193 -G1 X6.0872 Y10.1883 -G2 X6.1055 Y10.16 I-0.0414 J-0.0468 -G1 X6.1646 Y9.9686 -G1 X6.3697 Y9.9686 -G2 X6.4322 Y9.9061 I0 J-0.0625 -G2 X6.4064 Y9.8555 I-0.0625 J0 -G1 X6.243 Y9.7368 -G1 X6.3053 Y9.5447 -G2 X6.3084 Y9.5254 I-0.0594 J-0.0193 -G2 X6.2092 Y9.4748 I-0.0625 J0 -G1 X6.0458 Y9.5936 -G1 X5.8824 Y9.4748 -G2 X5.7831 Y9.5254 I-0.0367 J0.0506 -G2 X5.7862 Y9.5447 I0.0625 J0 -G1 X5.8487 Y9.7368 -G1 X5.6853 Y9.8555 -G2 X5.6595 Y9.9061 I0.0367 J0.0506 -G2 X5.722 Y9.9686 I0.0625 J0 -G1 X5.9239 Y9.9686 -G1 X5.9863 Y10.1608 -G2 X6.0043 Y10.1883 I0.0594 J-0.0193 -G1 X4.8216 Y10.1883 -G2 X4.8399 Y10.1599 I-0.0414 J-0.0468 -G1 X4.899 Y9.9686 -G1 X5.104 Y9.9686 -G2 X5.1665 Y9.9061 I0 J-0.0625 -G2 X5.1407 Y9.8555 I-0.0625 J0 -G1 X4.9773 Y9.7368 -G1 X5.0398 Y9.5447 -G2 X5.0428 Y9.5254 I-0.0594 J-0.0193 -G2 X4.9436 Y9.4748 I-0.0625 J0 -G0 Z0.25 -G0 X3.3884 Y5.1883 -G1 Z-0.05 F30 -G1 X3.6406 Y5.1883 F10 -G1 X3.5145 Y5.28 -G1 X3.3884 Y5.1883 -G0 Z0.25 -G0 X0.8571 Y5.1883 -G1 Z-0.05 F30 -G1 X1.1094 Y5.1883 F10 -G1 X0.9833 Y5.28 -G1 X0.8571 Y5.1883 -G0 Z0.25 -G0 X7.1853 Y5.1883 -G1 Z-0.05 F30 -G1 X7.4376 Y5.1883 F10 -G1 X7.3115 Y5.28 -G1 X7.1853 Y5.1883 -G0 Z0.25 -G0 X4.6541 Y5.1883 -G1 Z-0.05 F30 -G1 X4.9063 Y5.1883 F10 -G1 X4.7802 Y5.28 -G1 X4.6541 Y5.1883 -G0 Z0.25 -G0 X2.1228 Y5.1883 -G1 Z-0.05 F30 -G1 X2.3751 Y5.1883 F10 -G1 X2.249 Y5.28 -G1 X2.1228 Y5.1883 -G0 Z0.25 -G0 X5.9196 Y5.1883 -G1 Z-0.05 F30 -G1 X6.1719 Y5.1883 F10 -G1 X6.0458 Y5.28 -G1 X5.9196 Y5.1883 - -(follow path 2) -G0 Z0.25 -G0 X0.3505 Y1.1448 -G1 Z-0.0625 F30 -G1 X19.3505 Y1.1448 F10 -G1 X19.3505 Y0.3758 -G1 X0.3505 Y0.3758 -G1 X0.3505 Y1.1448 -G0 Z0.25 -G0 X0.3505 Y1.9144 -G1 Z-0.0625 F30 -G1 X19.3505 Y1.9144 F10 -G1 X19.3505 Y1.1454 -G1 X0.3505 Y1.1454 -G1 X0.3505 Y1.9144 -G0 Z0.25 -G0 X0.3505 Y2.6842 -G1 Z-0.0625 F30 -G1 X19.3505 Y2.6842 F10 -G1 X19.3505 Y1.9152 -G1 X0.3505 Y1.9152 -G1 X0.3505 Y2.6842 -G0 Z0.25 -G0 X0.3505 Y3.4537 -G1 Z-0.0625 F30 -G1 X19.3505 Y3.4537 F10 -G1 X19.3505 Y2.6847 -G1 X0.3505 Y2.6847 -G1 X0.3505 Y3.4537 -G0 Z0.25 -G0 X0.3505 Y4.2232 -G1 Z-0.0625 F30 -G1 X19.3505 Y4.2232 F10 -G1 X19.3505 Y3.4542 -G1 X0.3505 Y3.4542 -G1 X0.3505 Y4.2232 -G0 Z0.25 -G0 X0.3505 Y4.9927 -G1 Z-0.0625 F30 -G1 X19.3505 Y4.9927 F10 -G1 X19.3505 Y4.2237 -G1 X0.3505 Y4.2237 -G1 X0.3505 Y4.9927 -G0 Z0.25 -G0 X7.952 Y5.7625 -G1 Z-0.0625 F30 -G1 X19.3505 Y5.7625 F10 -G1 X19.3505 Y4.9935 -G1 X7.952 Y4.9935 -G1 X7.952 Y5.7625 -G0 Z0.25 -G0 X7.952 Y6.5321 -G1 Z-0.0625 F30 -G1 X19.3505 Y6.5321 F10 -G1 X19.3505 Y5.7631 -G1 X7.952 Y5.7631 -G1 X7.952 Y6.5321 -G0 Z0.25 -G0 X7.952 Y7.3011 -G1 Z-0.0625 F30 -G1 X19.3505 Y7.3011 F10 -G1 X19.3505 Y6.5321 -G1 X7.952 Y6.5321 -G1 X7.952 Y7.3011 -G0 Z0.25 -G0 X7.952 Y8.0706 -G1 Z-0.0625 F30 -G1 X19.3505 Y8.0706 F10 -G1 X19.3505 Y7.3016 -G1 X7.952 Y7.3016 -G1 X7.952 Y8.0706 -G0 Z0.25 -G0 X7.952 Y8.8404 -G1 Z-0.0625 F30 -G1 X19.3505 Y8.8404 F10 -G1 X19.3505 Y8.0714 -G1 X7.952 Y8.0714 -G1 X7.952 Y8.8404 -G0 Z0.25 -G0 X7.952 Y9.6099 -G1 Z-0.0625 F30 -G1 X19.3505 Y9.6099 F10 -G1 X19.3505 Y8.8409 -G1 X7.952 Y8.8409 -G1 X7.952 Y9.6099 -G0 Z0.25 -G0 X7.952 Y10.3795 -G1 Z-0.0625 F30 -G1 X19.3505 Y10.3795 F10 -G1 X19.3505 Y9.6105 -G1 X7.952 Y9.6105 -G1 X7.952 Y10.3795 -G0 Z0.25 -G0 X0.3505 Y10.3758 -G1 Z-0.0625 F30 -G1 X7.9505 Y10.3758 F10 -G1 X7.9505 Y4.9908 -G1 X0.3505 Y4.9908 -G1 X0.3505 Y10.3758 - -(profile 3) -G0 Z0.25 -T0 M6 -G0 X0.1005 Y0.0008 -G1 Z-0.15 F30 -G1 X18.694 Y0.0008 F20 -G1 X19.194 Y0.0008 -G1 X19.6005 Y0.0008 -G3 X19.7255 Y0.1258 I0 J0.125 -G1 X19.7255 Y9.6604 -G1 X19.7255 Y10.1604 -G1 X19.7255 Y10.6258 -G3 X19.6005 Y10.7508 I-0.125 J0 -G1 X1.1894 Y10.7508 -G1 X0.6894 Y10.7508 -G1 X0.1005 Y10.7508 -G3 X-0.0245 Y10.6258 I0 J-0.125 -G1 X-0.0245 Y0.9697 -G1 X-0.0245 Y0.4697 -G1 X-0.0245 Y0.1258 -G3 X0.1005 Y0.0008 I0.125 J0 -G1 Z-0.3 F30 -G1 X18.694 Y0.0008 F20 -G1 X19.194 Y0.0008 -G1 X19.6005 Y0.0008 -G3 X19.7255 Y0.1258 I0 J0.125 -G1 X19.7255 Y9.6604 -G1 X19.7255 Y10.1604 -G1 X19.7255 Y10.6258 -G3 X19.6005 Y10.7508 I-0.125 J0 -G1 X1.1894 Y10.7508 -G1 X0.6894 Y10.7508 -G1 X0.1005 Y10.7508 -G3 X-0.0245 Y10.6258 I0 J-0.125 -G1 X-0.0245 Y0.9697 -G1 X-0.0245 Y0.4697 -G1 X-0.0245 Y0.1258 -G3 X0.1005 Y0.0008 I0.125 J0 -G1 Z-0.45 F30 -G1 X18.694 Y0.0008 F20 -G1 X19.194 Y0.0008 -G1 X19.6005 Y0.0008 -G3 X19.7255 Y0.1258 I0 J0.125 -G1 X19.7255 Y9.6604 -G1 X19.7255 Y10.1604 -G1 X19.7255 Y10.6258 -G3 X19.6005 Y10.7508 I-0.125 J0 -G1 X1.1894 Y10.7508 -G1 X0.6894 Y10.7508 -G1 X0.1005 Y10.7508 -G3 X-0.0245 Y10.6258 I0 J-0.125 -G1 X-0.0245 Y0.9697 -G1 X-0.0245 Y0.4697 -G1 X-0.0245 Y0.1258 -G3 X0.1005 Y0.0008 I0.125 J0 -G1 Z-0.6 F30 -G1 X18.694 Y0.0008 F20 -G1 X19.194 Y0.0008 -G1 X19.6005 Y0.0008 -G3 X19.7255 Y0.1258 I0 J0.125 -G1 X19.7255 Y9.6604 -G1 X19.7255 Y10.1604 -G1 X19.7255 Y10.6258 -G3 X19.6005 Y10.7508 I-0.125 J0 -G1 X1.1894 Y10.7508 -G1 X0.6894 Y10.7508 -G1 X0.1005 Y10.7508 -G3 X-0.0245 Y10.6258 I0 J-0.125 -G1 X-0.0245 Y0.9697 -G1 X-0.0245 Y0.4697 -G1 X-0.0245 Y0.1258 -G3 X0.1005 Y0.0008 I0.125 J0 -G1 Z-0.75 F30 -G1 X18.694 Y0.0008 F20 -G1 Z-0.6 F30 -G1 X19.194 Y0.0008 F20 -G1 Z-0.75 F30 -G1 X19.6005 Y0.0008 F20 -G3 X19.7255 Y0.1258 I0 J0.125 -G1 X19.7255 Y9.6604 -G1 Z-0.6 F30 -G1 X19.7255 Y10.1604 F20 -G1 Z-0.75 F30 -G1 X19.7255 Y10.6258 F20 -G3 X19.6005 Y10.7508 I-0.125 J0 -G1 X1.1894 Y10.7508 -G1 Z-0.6 F30 -G1 X0.6894 Y10.7508 F20 -G1 Z-0.75 F30 -G1 X0.1005 Y10.7508 F20 -G3 X-0.0245 Y10.6258 I0 J-0.125 -G1 X-0.0245 Y0.9697 -G1 Z-0.6 F30 -G1 X-0.0245 Y0.4697 F20 -G1 Z-0.75 F30 -G1 X-0.0245 Y0.1258 F20 -G3 X0.1005 Y0.0008 I0.125 J0 -G1 Z-0.85 F30 -G1 X18.694 Y0.0008 F20 -G1 Z-0.6 F30 -G1 X19.194 Y0.0008 F20 -G1 Z-0.85 F30 -G1 X19.6005 Y0.0008 F20 -G3 X19.7255 Y0.1258 I0 J0.125 -G1 X19.7255 Y9.6604 -G1 Z-0.6 F30 -G1 X19.7255 Y10.1604 F20 -G1 Z-0.85 F30 -G1 X19.7255 Y10.6258 F20 -G3 X19.6005 Y10.7508 I-0.125 J0 -G1 X1.1894 Y10.7508 -G1 Z-0.6 F30 -G1 X0.6894 Y10.7508 F20 -G1 Z-0.85 F30 -G1 X0.1005 Y10.7508 F20 -G3 X-0.0245 Y10.6258 I0 J-0.125 -G1 X-0.0245 Y0.9697 -G1 Z-0.6 F30 -G1 X-0.0245 Y0.4697 F20 -G1 Z-0.85 F30 -G1 X-0.0245 Y0.1258 F20 -G3 X0.1005 Y0.0008 I0.125 J0 -G0 Z0.25 -M5 -M30 diff --git a/gcode/flag5-a-optimized.nc b/gcode/flag5-a-optimized.nc deleted file mode 100644 index 12bbfbe5..00000000 --- a/gcode/flag5-a-optimized.nc +++ /dev/null @@ -1,3361 +0,0 @@ -(Optimized by \gcodemillopt.exe) -(Written by Andrew L. Sandoval) -(Generated by PartKam Version 0.05) - -G20 G90 G40 - -(pocket 1) -T1 M6 -G17 -M3 -G0 X0.491 Y3.7656 -G1 Z-0.05 F30 -G1 X0.491 Y3.6486 F10 -G1 X0.5066 Y3.6486 -G1 X0.5344 Y3.7341 -G1 X0.491 Y3.7656 -G0 Z0.25 -G0 X0.7129 Y3.5986 -G1 Z-0.05 F30 -G1 X0.8059 Y3.5986 F10 -G1 X0.7594 Y3.6324 -G1 X0.7129 Y3.5986 -G0 Z0.25 -G0 X1.1643 Y3.7486 -G1 Z-0.05 F30 -G1 X1.3037 Y3.7486 F10 -G2 X1.2602 Y3.8323 I0.162 J0.1375 -G2 X1.2593 Y3.833 I0.124 J0.1726 -G1 X1.234 Y3.8513 -G1 X1.2087 Y3.8329 -G2 X1.2079 Y3.8323 I-0.1249 J0.172 -G2 X1.1643 Y3.7486 I-0.2056 J0.0538 -G1 X1.0978 Y3.7547 F10 -G1 X1.0432 Y3.715 F10 -G1 X1.0485 Y3.6986 -G1 X1.4195 Y3.6986 -G1 X1.4248 Y3.715 -G1 X1.3702 Y3.7547 -G2 X1.3049 Y3.8631 I0.0955 J0.1315 -G2 X1.2887 Y3.8734 I0.0793 J0.1418 -G1 X1.234 Y3.9131 -G1 X1.1793 Y3.8734 -G2 X1.1631 Y3.8631 I-0.0955 J0.1315 -G2 X1.0978 Y3.7547 I-0.1609 J0.0231 -G1 X1.0684 Y3.7951 F10 -G1 X0.9844 Y3.7341 F10 -G1 X1.0122 Y3.6486 -G1 X1.4559 Y3.6486 -G1 X1.4836 Y3.7341 -G1 X1.3996 Y3.7951 -G2 X1.3532 Y3.8861 I0.0661 J0.091 -G2 X1.3537 Y3.8966 I0.1125 J0 -G2 X1.318 Y3.9139 I0.0305 J0.1083 -G1 X1.234 Y3.9749 -G1 X1.15 Y3.9139 -G2 X1.1143 Y3.8966 I-0.0661 J0.091 -G2 X1.1148 Y3.8861 I-0.112 J-0.0104 -G2 X1.0684 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X0.6048 Y4.1128 -G1 Z-0.05 F30 -G2 X0.8742 Y4.1776 I0.1546 J-0.0502 F10 -G2 X0.8763 Y4.1755 I-0.1148 J-0.115 -G2 X0.8742 Y4.1776 I0.1148 J0.115 -G2 X0.8303 Y4.2673 I0.1169 J0.1129 -G2 X0.814 Y4.2777 I0.0792 J0.1419 -G1 X0.7594 Y4.3174 -G1 X0.7048 Y4.2777 -G2 X0.541 Y4.2617 I-0.0955 J0.1315 -G1 X0.541 Y4.0486 -G1 X0.584 Y4.0486 -G1 X0.6048 Y4.1128 -G1 X0.6524 Y4.0973 F10 -G2 X0.8669 Y4.0958 I0.107 J-0.0347 F10 -G1 X0.8969 Y3.9986 -G1 X0.9715 Y3.9986 -G2 X0.9714 Y4.0049 I0.1123 J0.0062 -G2 X0.9769 Y4.0397 I0.1125 J0 -G1 X1.009 Y4.1384 -G1 X0.925 Y4.1994 -G2 X0.8787 Y4.2904 I0.0661 J0.091 -G2 X0.8791 Y4.3008 I0.1125 J0 -G2 X0.8434 Y4.3182 I0.0303 J0.1083 -G1 X0.7594 Y4.3792 -G1 X0.6754 Y4.3182 -G2 X0.4968 Y4.4092 I-0.0661 J0.091 -G2 X0.5023 Y4.444 I0.1125 J0 -G1 X0.5344 Y4.5427 -G1 X0.491 Y4.5742 -G1 X0.491 Y3.9957 -G2 X0.5166 Y3.9986 I0.0255 J-0.1096 -G1 X0.6203 Y3.9986 -G1 X0.6524 Y4.0973 -G0 Z0.25 -G0 X0.8601 Y4.7572 -G1 Z-0.05 F30 -G1 X0.8191 Y4.8896 F10 -G3 X0.6999 Y4.8904 I-0.0597 J-0.0185 -G1 X0.6567 Y4.7572 -G1 X0.5166 Y4.7572 -G3 X0.4541 Y4.6947 I0 J-0.0625 -G3 X0.4798 Y4.6441 I0.0625 J0 -G1 X0.5932 Y4.5618 -G1 X0.5498 Y4.4285 -G3 X0.5468 Y4.4092 I0.0594 J-0.0193 -G3 X0.646 Y4.3586 I0.0625 J0 -G1 X0.7594 Y4.441 -G1 X0.8727 Y4.3586 -G3 X0.972 Y4.4092 I0.0367 J0.0506 -G3 X0.9689 Y4.4285 I-0.0625 J0 -G1 X0.9257 Y4.5617 -G1 X1.039 Y4.6441 -G3 X1.0648 Y4.6947 I-0.0367 J0.0506 -G3 X1.0023 Y4.7572 I-0.0625 J0 -G1 X0.8601 Y4.7572 -G0 Z0.25 -G0 X0.6048 Y4.9213 -G1 Z-0.05 F30 -G2 X0.9146 Y4.9192 I0.1546 J-0.0502 F10 -G1 X0.9306 Y4.8676 -G1 X0.9502 Y4.928 -G1 X0.8956 Y4.9676 -G2 X0.8302 Y5.0768 I0.0955 J0.1315 -G2 X0.814 Y5.0872 I0.0793 J0.1418 -G1 X0.7594 Y5.1268 -G1 X0.7048 Y5.0872 -G2 X0.541 Y5.0712 I-0.0955 J0.1315 -G1 X0.541 Y4.8572 -G1 X0.584 Y4.8572 -G1 X0.6048 Y4.9213 -G1 X0.6524 Y4.9059 F10 -G2 X0.8669 Y4.9044 I0.107 J-0.0347 F10 -G1 X0.8969 Y4.8072 -G1 X0.9715 Y4.8072 -G2 X0.9714 Y4.8135 I0.1123 J0.0064 -G2 X0.9769 Y4.8483 I0.1125 J0 -G1 X1.009 Y4.947 -G1 X0.925 Y5.008 -G2 X0.8787 Y5.0991 I0.0661 J0.091 -G2 X0.8792 Y5.1103 I0.1125 J0 -G2 X0.8434 Y5.1276 I0.0303 J0.1084 -G1 X0.7594 Y5.1886 -G1 X0.6754 Y5.1276 -G2 X0.4968 Y5.2186 I-0.0661 J0.091 -G2 X0.5023 Y5.2534 I0.1125 J0 -G1 X0.5344 Y5.3521 -G1 X0.491 Y5.3836 -G1 X0.491 Y4.8043 -G2 X0.5166 Y4.8072 I0.0255 J-0.1096 -G1 X0.6203 Y4.8072 -G1 X0.6524 Y4.9059 -G0 Z0.25 -G0 X1.1192 Y4.5818 -G1 Z-0.05 F30 -G2 X1.3473 Y4.5835 I0.1148 J-0.115 F10 -G2 X1.3049 Y4.6717 I0.1185 J0.1112 -G2 X1.2887 Y4.682 I0.0793 J0.1418 -G1 X1.234 Y4.7218 -G1 X1.1794 Y4.6821 -G2 X1.1632 Y4.6717 I-0.0955 J0.1315 -G2 X1.1192 Y4.5818 I-0.1609 J0.023 -G2 X1.1171 Y4.5797 I-0.1169 J0.1129 -G2 X1.1192 Y4.5818 I0.1169 J-0.1129 -G0 Z0.25 -G0 X1.3525 Y4.5781 -G1 Z-0.05 F30 -G2 X1.3893 Y4.5148 I-0.1185 J-0.1112 F10 -G1 X1.4053 Y4.4632 -G1 X1.4248 Y4.5235 -G1 X1.3702 Y4.5632 -G2 X1.3525 Y4.5781 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.3996 Y4.6037 -G1 Z-0.05 F30 -G2 X1.3532 Y4.6947 I0.0661 J0.091 F10 -G2 X1.3537 Y4.7052 I0.1125 J0 -G2 X1.3181 Y4.7225 I0.0304 J0.1083 -G1 X1.234 Y4.7836 -G1 X1.15 Y4.7225 -G2 X1.1143 Y4.7052 I-0.0661 J0.091 -G2 X1.1148 Y4.6947 I-0.112 J-0.0106 -G2 X1.0684 Y4.6037 I-0.1125 J0 -G1 X0.9844 Y4.5426 -G1 X1.0165 Y4.4439 -G2 X1.022 Y4.4092 I-0.107 J-0.0347 -G2 X1.0218 Y4.4029 I-0.1125 J0 -G1 X1.095 Y4.4029 -G1 X1.1271 Y4.5017 -G2 X1.3416 Y4.5001 I0.107 J-0.0348 -G1 X1.3716 Y4.4029 -G1 X1.4462 Y4.4029 -G2 X1.446 Y4.4092 I0.1123 J0.0062 -G2 X1.4515 Y4.4439 I0.1125 J0 -G1 X1.4836 Y4.5426 -G1 X1.3996 Y4.6037 -G0 Z0.25 -G0 X1.3347 Y4.3529 -G1 Z-0.05 F30 -G1 X1.2938 Y4.4853 F10 -G3 X1.1746 Y4.4862 I-0.0597 J-0.0184 -G1 X1.1313 Y4.3529 -G1 X0.9912 Y4.3529 -G3 X0.9287 Y4.2904 I0 J-0.0625 -G3 X0.9544 Y4.2399 I0.0625 J0 -G1 X1.0678 Y4.1575 -G1 X1.0244 Y4.0242 -G3 X1.0214 Y4.0049 I0.0594 J-0.0193 -G3 X1.1206 Y3.9543 I0.0625 J0 -G1 X1.2341 Y4.0367 -G1 X1.3474 Y3.9543 -G3 X1.4467 Y4.0049 I0.0367 J0.0506 -G3 X1.4436 Y4.0242 I-0.0625 J0 -G1 X1.4003 Y4.1575 -G1 X1.5136 Y4.2399 -G3 X1.5394 Y4.2904 I-0.0367 J0.0506 -G3 X1.4769 Y4.3529 I-0.0625 J0 -G1 X1.3347 Y4.3529 -G0 Z0.25 -G0 X1.5938 Y4.1776 -G1 Z-0.05 F30 -G2 X1.8218 Y4.1792 I0.1148 J-0.115 F10 -G2 X1.7795 Y4.2673 I0.1185 J0.1112 -G2 X1.7632 Y4.2777 I0.0793 J0.1418 -G1 X1.7087 Y4.3174 -G1 X1.6541 Y4.2777 -G2 X1.6377 Y4.2673 I-0.0955 J0.1315 -G2 X1.5938 Y4.1776 I-0.1608 J0.0232 -G2 X1.5917 Y4.1755 I-0.1169 J0.1129 -G2 X1.5938 Y4.1776 I0.1169 J-0.1129 -G0 Z0.25 -G0 X1.8271 Y4.1738 -G1 Z-0.05 F30 -G2 X1.8639 Y4.1105 I-0.1185 J-0.1112 F10 -G1 X1.8798 Y4.059 -G1 X1.8994 Y4.1193 -G1 X1.8448 Y4.159 -G2 X1.8271 Y4.1738 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.8742 Y4.1994 -G1 Z-0.05 F30 -G2 X1.8278 Y4.2904 I0.0661 J0.091 F10 -G2 X1.8283 Y4.3009 I0.1125 J0 -G2 X1.7926 Y4.3182 I0.0305 J0.1083 -G1 X1.7087 Y4.3792 -G1 X1.6247 Y4.3182 -G2 X1.5889 Y4.3008 I-0.0661 J0.091 -G2 X1.5894 Y4.2904 I-0.112 J-0.0104 -G2 X1.543 Y4.1994 I-0.1125 J0 -G1 X1.4591 Y4.1384 -G1 X1.4912 Y4.0397 -G2 X1.4967 Y4.0049 I-0.107 J-0.0348 -G2 X1.4965 Y3.9986 I-0.1125 J0 -G1 X1.5695 Y3.9986 -G1 X1.6017 Y4.0974 -G2 X1.8161 Y4.0958 I0.107 J-0.0348 -G1 X1.8461 Y3.9986 -G1 X1.9208 Y3.9986 -G2 X1.9206 Y4.0049 I0.1123 J0.0062 -G2 X1.9261 Y4.0396 I0.1125 J0 -G1 X1.9582 Y4.1384 -G1 X1.8742 Y4.1994 -G0 Z0.25 -G0 X2.2839 Y4.3529 -G1 Z-0.05 F30 -G1 X2.2429 Y4.4853 F10 -G3 X2.1238 Y4.4862 I-0.0597 J-0.0185 -G1 X2.0805 Y4.3529 -G1 X1.9403 Y4.3529 -G3 X1.8778 Y4.2904 I0 J-0.0625 -G3 X1.9036 Y4.2399 I0.0625 J0 -G1 X2.017 Y4.1575 -G1 X1.9737 Y4.0242 -G3 X1.9706 Y4.0049 I0.0594 J-0.0193 -G3 X2.0699 Y3.9543 I0.0625 J0 -G1 X2.1832 Y4.0367 -G1 X2.2966 Y3.9543 -G3 X2.3958 Y4.0049 I0.0367 J0.0506 -G3 X2.3928 Y4.0242 I-0.0625 J0 -G1 X2.3495 Y4.1575 -G1 X2.4629 Y4.2399 -G3 X2.4887 Y4.2904 I-0.0367 J0.0506 -G3 X2.4262 Y4.3529 I-0.0625 J0 -G1 X2.2839 Y4.3529 -G0 Z0.25 -G0 X2.3002 Y4.5797 -G1 Z-0.05 F30 -G2 X2.3385 Y4.5149 I-0.1169 J-0.1129 F10 -G1 X2.3544 Y4.4633 -G1 X2.3741 Y4.5236 -G1 X2.3195 Y4.5632 -G2 X2.3002 Y4.5797 I0.0955 J0.1315 -G0 Z0.25 -G0 X2.3489 Y4.6037 -G1 Z-0.05 F30 -G2 X2.3025 Y4.6947 I0.0661 J0.091 F10 -G2 X2.303 Y4.7052 I0.1125 J0 -G2 X2.2672 Y4.7225 I0.0303 J0.1083 -G1 X2.1832 Y4.7835 -G1 X2.0993 Y4.7225 -G2 X2.0635 Y4.7052 I-0.0661 J0.091 -G2 X2.064 Y4.6947 I-0.112 J-0.0105 -G2 X2.0176 Y4.6037 I-0.1125 J0 -G1 X1.9336 Y4.5427 -G1 X1.9657 Y4.444 -G2 X1.9713 Y4.4092 I-0.107 J-0.0348 -G2 X1.9711 Y4.4029 I-0.1125 J0 -G1 X2.0442 Y4.4029 -G1 X2.0762 Y4.5016 -G2 X2.2907 Y4.5001 I0.107 J-0.0347 -G1 X2.3208 Y4.4029 -G1 X2.3954 Y4.4029 -G2 X2.3952 Y4.4092 I0.1123 J0.0062 -G2 X2.4007 Y4.444 I0.1125 J0 -G1 X2.4328 Y4.5427 -G1 X2.3489 Y4.6037 -G0 Z0.25 -G0 X2.0684 Y4.5818 -G1 Z-0.05 F30 -G2 X2.2981 Y4.5818 I0.1148 J-0.115 F10 -G2 X2.2541 Y4.6716 I0.1169 J0.1129 -G2 X2.2378 Y4.6821 I0.0792 J0.1419 -G1 X2.1832 Y4.7217 -G1 X2.1286 Y4.6821 -G2 X2.1123 Y4.6716 I-0.0955 J0.1315 -G2 X2.0684 Y4.5818 I-0.1609 J0.023 -G2 X2.0663 Y4.5797 I-0.1169 J0.1129 -G2 X2.0684 Y4.5818 I0.1169 J-0.1129 -G0 Z0.25 -G0 X1.8092 Y4.7572 -G1 Z-0.05 F30 -G1 X1.7684 Y4.8896 F10 -G3 X1.6492 Y4.8905 I-0.0597 J-0.0184 -G1 X1.6059 Y4.7572 -G1 X1.4657 Y4.7572 -G3 X1.4032 Y4.6947 I0 J-0.0625 -G3 X1.429 Y4.6441 I0.0625 J0 -G1 X1.5424 Y4.5617 -G1 X1.4991 Y4.4285 -G3 X1.496 Y4.4092 I0.0594 J-0.0193 -G3 X1.5953 Y4.3586 I0.0625 J0 -G1 X1.7087 Y4.441 -G1 X1.822 Y4.3586 -G3 X1.9213 Y4.4092 I0.0367 J0.0506 -G3 X1.9182 Y4.4285 I-0.0625 J0 -G1 X1.8748 Y4.5618 -G1 X1.9882 Y4.6441 -G3 X2.014 Y4.6947 I-0.0367 J0.0506 -G3 X1.9515 Y4.7572 I-0.0625 J0 -G1 X1.8092 Y4.7572 -G0 Z0.25 -G0 X1.8256 Y4.984 -G1 Z-0.05 F30 -G2 X1.8639 Y4.9191 I-0.1169 J-0.1129 F10 -G1 X1.8798 Y4.8676 -G1 X1.8994 Y4.9279 -G1 X1.8448 Y4.9676 -G2 X1.8256 Y4.984 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.8742 Y5.008 -G1 Z-0.05 F30 -G2 X1.8278 Y5.0991 I0.0661 J0.091 F10 -G2 X1.8284 Y5.1103 I0.1125 J0 -G2 X1.7926 Y5.1276 I0.0304 J0.1083 -G1 X1.7087 Y5.1886 -G1 X1.6247 Y5.1276 -G2 X1.5888 Y5.1103 I-0.0661 J0.091 -G2 X1.5894 Y5.0991 I-0.1119 J-0.0112 -G2 X1.543 Y5.008 I-0.1125 J0 -G1 X1.4591 Y4.947 -G1 X1.4912 Y4.8483 -G2 X1.4967 Y4.8135 I-0.107 J-0.0348 -G2 X1.4965 Y4.8072 I-0.1125 J0 -G1 X1.5695 Y4.8072 -G1 X1.6017 Y4.9059 -G2 X1.8161 Y4.9043 I0.107 J-0.0348 -G1 X1.8461 Y4.8072 -G1 X1.9208 Y4.8072 -G2 X1.9206 Y4.8135 I0.1123 J0.0064 -G2 X1.9261 Y4.8483 I0.1125 J0 -G1 X1.9582 Y4.947 -G1 X1.8742 Y5.008 -G0 Z0.25 -G0 X1.5541 Y4.9214 -G1 Z-0.05 F30 -G2 X1.8234 Y4.9862 I0.1545 J-0.0503 F10 -G2 X1.7793 Y5.0769 I0.1169 J0.1129 -G2 X1.7632 Y5.0872 I0.0794 J0.1418 -G1 X1.7087 Y5.1268 -G1 X1.6541 Y5.0872 -G2 X1.6379 Y5.0768 I-0.0955 J0.1315 -G2 X1.5724 Y4.9676 I-0.161 J0.0223 -G1 X1.5178 Y4.928 -G1 X1.537 Y4.8689 -G1 X1.5541 Y4.9214 -G0 Z0.25 -G0 X1.3346 Y5.1616 -G1 Z-0.05 F30 -G1 X1.2937 Y5.294 F10 -G3 X1.1745 Y5.2948 I-0.0597 J-0.0185 -G1 X1.1313 Y5.1616 -G1 X0.9912 Y5.1616 -G3 X0.9287 Y5.0991 I0 J-0.0625 -G3 X0.9544 Y5.0485 I0.0625 J0 -G1 X1.0678 Y4.9661 -G1 X1.0244 Y4.8329 -G3 X1.0214 Y4.8135 I0.0594 J-0.0193 -G3 X1.1206 Y4.763 I0.0625 J0 -G1 X1.234 Y4.8454 -G1 X1.3475 Y4.763 -G3 X1.4467 Y4.8135 I0.0367 J0.0506 -G3 X1.4436 Y4.8329 I-0.0625 J0 -G1 X1.4003 Y4.9661 -G1 X1.5136 Y5.0485 -G3 X1.5394 Y5.0991 I-0.0367 J0.0506 -G3 X1.4769 Y5.1616 I-0.0625 J0 -G1 X1.3346 Y5.1616 -G0 Z0.25 -G0 X1.0794 Y5.3257 -G1 Z-0.05 F30 -G2 X1.3892 Y5.3235 I0.1546 J-0.0502 F10 -G1 X1.4051 Y5.2722 -G1 X1.4248 Y5.333 -G1 X1.3702 Y5.3727 -G2 X1.305 Y5.4802 I0.0955 J0.1315 -G2 X1.2887 Y5.4906 I0.0792 J0.1419 -G1 X1.234 Y5.5303 -G1 X1.1793 Y5.4906 -G2 X1.163 Y5.4802 I-0.0955 J0.1315 -G2 X1.0978 Y5.3727 I-0.1607 J0.024 -G1 X1.0432 Y5.333 -G1 X1.0625 Y5.2736 -G1 X1.0794 Y5.3257 -G1 X1.127 Y5.3103 F10 -G2 X1.3414 Y5.3088 I0.107 J-0.0347 F10 -G1 X1.3715 Y5.2116 -G1 X1.4463 Y5.2116 -G2 X1.446 Y5.2186 I0.1123 J0.0071 -G2 X1.4515 Y5.2534 I0.1125 J0 -G1 X1.4836 Y5.3521 -G1 X1.3996 Y5.4132 -G2 X1.3532 Y5.5042 I0.0661 J0.091 -G2 X1.3536 Y5.5138 I0.1125 J0 -G2 X1.318 Y5.5311 I0.0305 J0.1083 -G1 X1.234 Y5.5921 -G1 X1.15 Y5.531 -G2 X1.1144 Y5.5138 I-0.0661 J0.091 -G2 X1.1148 Y5.5042 I-0.1121 J-0.0096 -G2 X1.0684 Y5.4132 I-0.1125 J0 -G1 X0.9844 Y5.3521 -G1 X1.0165 Y5.2534 -G2 X1.022 Y5.2186 I-0.107 J-0.0347 -G2 X1.0218 Y5.2116 I-0.1125 J0 -G1 X1.0949 Y5.2116 -G1 X1.127 Y5.3103 -G0 Z0.25 -G0 X0.8601 Y5.5667 -G1 Z-0.05 F30 -G1 X0.8191 Y5.6992 F10 -G3 X0.6999 Y5.7 I-0.0597 J-0.0185 -G1 X0.6567 Y5.5667 -G1 X0.5166 Y5.5667 -G3 X0.4541 Y5.5042 I0 J-0.0625 -G3 X0.4798 Y5.4536 I0.0625 J0 -G1 X0.5932 Y5.3712 -G1 X0.5498 Y5.238 -G3 X0.5468 Y5.2186 I0.0594 J-0.0193 -G3 X0.646 Y5.1681 I0.0625 J0 -G1 X0.7594 Y5.2505 -G1 X0.8727 Y5.1681 -G3 X0.972 Y5.2186 I0.0367 J0.0506 -G3 X0.9689 Y5.2379 I-0.0625 J0 -G1 X0.9257 Y5.3712 -G1 X1.039 Y5.4536 -G3 X1.0648 Y5.5042 I-0.0367 J0.0506 -G3 X1.0023 Y5.5667 I-0.0625 J0 -G1 X0.8601 Y5.5667 -G0 Z0.25 -G0 X0.6048 Y5.7309 -G1 Z-0.05 F30 -G2 X0.868 Y5.8016 I0.1546 J-0.0502 F10 -G2 X0.8826 Y5.7867 I-0.1086 J-0.1209 -G2 X0.868 Y5.8016 I0.1086 J0.1209 -G2 X0.8303 Y5.8844 I0.1232 J0.106 -G2 X0.814 Y5.8949 I0.0792 J0.1419 -G1 X0.7594 Y5.9346 -G1 X0.7048 Y5.8949 -G2 X0.541 Y5.8789 I-0.0955 J0.1315 -G1 X0.541 Y5.6667 -G1 X0.584 Y5.6667 -G1 X0.6048 Y5.7309 -G1 X0.6524 Y5.7155 F10 -G2 X0.8669 Y5.714 I0.107 J-0.0347 F10 -G1 X0.8969 Y5.6167 -G1 X0.9715 Y5.6167 -G2 X0.9714 Y5.6221 I0.1124 J0.0054 -G2 X0.9769 Y5.6569 I0.1125 J0 -G1 X1.009 Y5.7556 -G1 X0.925 Y5.8166 -G2 X0.8787 Y5.9076 I0.0661 J0.091 -G2 X0.8791 Y5.918 I0.1125 J0 -G2 X0.8434 Y5.9353 I0.0303 J0.1083 -G1 X0.7594 Y5.9964 -G1 X0.6754 Y5.9353 -G2 X0.4968 Y6.0264 I-0.0661 J0.091 -G2 X0.5023 Y6.0612 I0.1125 J0 -G1 X0.5344 Y6.1599 -G1 X0.491 Y6.1914 -G1 X0.491 Y5.6137 -G2 X0.5166 Y5.6167 I0.0255 J-0.1096 -G1 X0.6203 Y5.6167 -G1 X0.6524 Y5.7155 -G0 Z0.25 -G0 X0.8601 Y6.3744 -G1 Z-0.05 F30 -G1 X0.8191 Y6.5068 F10 -G3 X0.6999 Y6.5076 I-0.0597 J-0.0185 -G1 X0.6567 Y6.3744 -G1 X0.5166 Y6.3744 -G3 X0.4541 Y6.3119 I0 J-0.0625 -G3 X0.4798 Y6.2613 I0.0625 J0 -G1 X0.5932 Y6.1789 -G1 X0.5498 Y6.0457 -G3 X0.5468 Y6.0264 I0.0594 J-0.0193 -G3 X0.646 Y5.9758 I0.0625 J0 -G1 X0.7594 Y6.0582 -G1 X0.8727 Y5.9758 -G3 X0.972 Y6.0264 I0.0367 J0.0506 -G3 X0.9689 Y6.0457 I-0.0625 J0 -G1 X0.9257 Y6.1789 -G1 X1.039 Y6.2613 -G3 X1.0648 Y6.3119 I-0.0367 J0.0506 -G3 X1.0023 Y6.3744 I-0.0625 J0 -G1 X0.8601 Y6.3744 -G0 Z0.25 -G0 X0.6048 Y6.5385 -G1 Z-0.05 F30 -G2 X0.9146 Y6.5364 I0.1546 J-0.0502 F10 -G1 X0.9306 Y6.4848 -G1 X0.9502 Y6.5451 -G1 X0.8956 Y6.5848 -G2 X0.8302 Y6.694 I0.0955 J0.1315 -G2 X0.814 Y6.7044 I0.0793 J0.1418 -G1 X0.7594 Y6.744 -G1 X0.7048 Y6.7044 -G2 X0.541 Y6.6884 I-0.0955 J0.1315 -G1 X0.541 Y6.4744 -G1 X0.584 Y6.4744 -G1 X0.6048 Y6.5385 -G1 X0.6524 Y6.5231 F10 -G2 X0.8669 Y6.5216 I0.107 J-0.0347 F10 -G1 X0.8969 Y6.4244 -G1 X0.9715 Y6.4244 -G2 X0.9714 Y6.4307 I0.1123 J0.0064 -G2 X0.9769 Y6.4655 I0.1125 J0 -G1 X1.009 Y6.5642 -G1 X0.925 Y6.6252 -G2 X0.8787 Y6.7162 I0.0661 J0.091 -G2 X0.8792 Y6.7275 I0.1125 J0 -G2 X0.8434 Y6.7448 I0.0303 J0.1084 -G1 X0.7594 Y6.8058 -G1 X0.6754 Y6.7448 -G2 X0.4968 Y6.8358 I-0.0661 J0.091 -G2 X0.5023 Y6.8706 I0.1125 J0 -G1 X0.5344 Y6.9693 -G1 X0.491 Y7.0008 -G1 X0.491 Y6.4214 -G2 X0.5166 Y6.4244 I0.0255 J-0.1096 -G1 X0.6203 Y6.4244 -G1 X0.6524 Y6.5231 -G0 Z0.25 -G0 X0.6312 Y7.2674 -G1 Z-0.05 F30 -G1 X0.491 Y7.2674 F10 -G1 X0.491 Y7.2309 -G2 X0.5166 Y7.2339 I0.0255 J-0.1096 -G1 X0.6203 Y7.2339 -G1 X0.6312 Y7.2674 -G0 Z0.25 -G0 X1.2583 Y7.1674 -G1 Z-0.05 F30 -G1 X1.2098 Y7.1674 F10 -G2 X1.2148 Y7.1214 I-0.2075 J-0.046 -G2 X1.2141 Y7.1043 I-0.2125 J0 -G2 X1.2539 Y7.1043 I0.0199 J-0.2116 -G2 X1.2532 Y7.1214 I0.2118 J0.0171 -G2 X1.2583 Y7.1674 I0.2125 J0 -G1 X1.3032 Y7.1214 F10 -G2 X1.3347 Y7.2174 I0.1625 J0 F10 -G1 X1.1334 Y7.2174 -G2 X1.1648 Y7.1214 I-0.1311 J-0.096 -G2 X1.0978 Y6.9899 I-0.1625 J0 -G1 X1.0432 Y6.9502 -G1 X1.0625 Y6.8908 -G1 X1.0794 Y6.9429 -G2 X1.3892 Y6.9407 I0.1546 J-0.0502 -G1 X1.4051 Y6.8894 -G1 X1.4248 Y6.9502 -G1 X1.3702 Y6.9899 -G2 X1.3032 Y7.1214 I0.0955 J0.1315 -G1 X1.3532 Y7.1214 F10 -G2 X1.4657 Y7.2339 I0.1125 J0 F10 -G1 X1.5695 Y7.2339 -G1 X1.5804 Y7.2674 -G1 X0.8866 Y7.2674 -G1 X0.8969 Y7.2339 -G1 X1.0023 Y7.2339 -G2 X1.1148 Y7.1214 I0 J-0.1125 -G2 X1.0684 Y7.0303 I-0.1125 J0 -G1 X0.9844 Y6.9693 -G1 X1.0165 Y6.8706 -G2 X1.022 Y6.8358 I-0.107 J-0.0347 -G2 X1.0218 Y6.8287 I-0.1125 J0 -G1 X1.0949 Y6.8287 -G1 X1.127 Y6.9274 -G2 X1.3414 Y6.926 I0.107 J-0.0347 -G1 X1.3715 Y6.8287 -G1 X1.4463 Y6.8287 -G2 X1.446 Y6.8358 I0.1123 J0.0071 -G2 X1.4515 Y6.8706 I0.1125 J0 -G1 X1.4836 Y6.9693 -G1 X1.3996 Y7.0303 -G2 X1.3532 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X1.3346 Y6.7787 -G1 Z-0.05 F30 -G1 X1.2937 Y6.9112 F10 -G3 X1.1745 Y6.912 I-0.0597 J-0.0185 -G1 X1.1313 Y6.7787 -G1 X0.9912 Y6.7787 -G3 X0.9287 Y6.7162 I0 J-0.0625 -G3 X0.9544 Y6.6657 I0.0625 J0 -G1 X1.0678 Y6.5833 -G1 X1.0244 Y6.4501 -G3 X1.0214 Y6.4307 I0.0594 J-0.0193 -G3 X1.1206 Y6.3802 I0.0625 J0 -G1 X1.234 Y6.4625 -G1 X1.3475 Y6.3802 -G3 X1.4467 Y6.4307 I0.0367 J0.0506 -G3 X1.4436 Y6.4501 I-0.0625 J0 -G1 X1.4003 Y6.5833 -G1 X1.5136 Y6.6657 -G3 X1.5394 Y6.7162 I-0.0367 J0.0506 -G3 X1.4769 Y6.7787 I-0.0625 J0 -G1 X1.3346 Y6.7787 -G0 Z0.25 -G0 X1.5541 Y6.5386 -G1 Z-0.05 F30 -G2 X1.8234 Y6.6034 I0.1545 J-0.0503 F10 -G2 X1.7793 Y6.6941 I0.1169 J0.1129 -G2 X1.7632 Y6.7044 I0.0794 J0.1418 -G1 X1.7087 Y6.744 -G1 X1.6541 Y6.7044 -G2 X1.6379 Y6.694 I-0.0955 J0.1315 -G2 X1.5724 Y6.5848 I-0.161 J0.0223 -G1 X1.5178 Y6.5451 -G1 X1.537 Y6.4861 -G1 X1.5541 Y6.5386 -G0 Z0.25 -G0 X1.8256 Y6.6012 -G1 Z-0.05 F30 -G2 X1.8639 Y6.5363 I-0.1169 J-0.1129 F10 -G1 X1.8798 Y6.4848 -G1 X1.8994 Y6.5451 -G1 X1.8448 Y6.5848 -G2 X1.8256 Y6.6012 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.8742 Y6.6252 -G1 Z-0.05 F30 -G2 X1.8278 Y6.7162 I0.0661 J0.091 F10 -G2 X1.8284 Y6.7275 I0.1125 J0 -G2 X1.7926 Y6.7448 I0.0304 J0.1083 -G1 X1.7087 Y6.8058 -G1 X1.6247 Y6.7448 -G2 X1.5888 Y6.7275 I-0.0661 J0.091 -G2 X1.5894 Y6.7162 I-0.1119 J-0.0112 -G2 X1.543 Y6.6252 I-0.1125 J0 -G1 X1.4591 Y6.5642 -G1 X1.4912 Y6.4655 -G2 X1.4967 Y6.4307 I-0.107 J-0.0348 -G2 X1.4965 Y6.4244 I-0.1125 J0 -G1 X1.5695 Y6.4244 -G1 X1.6017 Y6.5231 -G2 X1.8161 Y6.5215 I0.107 J-0.0348 -G1 X1.8461 Y6.4244 -G1 X1.9208 Y6.4244 -G2 X1.9206 Y6.4307 I0.1123 J0.0064 -G2 X1.9261 Y6.4655 I0.1125 J0 -G1 X1.9582 Y6.5642 -G1 X1.8742 Y6.6252 -G0 Z0.25 -G0 X1.8092 Y6.3744 -G1 Z-0.05 F30 -G1 X1.7684 Y6.5068 F10 -G3 X1.6492 Y6.5077 I-0.0597 J-0.0184 -G1 X1.6059 Y6.3744 -G1 X1.4657 Y6.3744 -G3 X1.4032 Y6.3119 I0 J-0.0625 -G3 X1.429 Y6.2613 I0.0625 J0 -G1 X1.5424 Y6.1789 -G1 X1.4991 Y6.0457 -G3 X1.496 Y6.0264 I0.0594 J-0.0193 -G3 X1.5953 Y5.9758 I0.0625 J0 -G1 X1.7087 Y6.0582 -G1 X1.822 Y5.9758 -G3 X1.9213 Y6.0264 I0.0367 J0.0506 -G3 X1.9182 Y6.0457 I-0.0625 J0 -G1 X1.8748 Y6.1789 -G1 X1.9882 Y6.2613 -G3 X2.014 Y6.3119 I-0.0367 J0.0506 -G3 X1.9515 Y6.3744 I-0.0625 J0 -G1 X1.8092 Y6.3744 -G0 Z0.25 -G0 X2.0684 Y6.199 -G1 Z-0.05 F30 -G2 X2.2981 Y6.199 I0.1148 J-0.115 F10 -G2 X2.2541 Y6.2888 I0.1169 J0.1129 -G2 X2.2378 Y6.2993 I0.0792 J0.1419 -G1 X2.1832 Y6.3389 -G1 X2.1286 Y6.2993 -G2 X2.1123 Y6.2888 I-0.0955 J0.1315 -G2 X2.0684 Y6.199 I-0.1609 J0.023 -G2 X2.0663 Y6.1969 I-0.1169 J0.1129 -G2 X2.0684 Y6.199 I0.1169 J-0.1129 -G0 Z0.25 -G0 X2.3002 Y6.1969 -G1 Z-0.05 F30 -G2 X2.3385 Y6.1321 I-0.1169 J-0.1129 F10 -G1 X2.3544 Y6.0805 -G1 X2.3741 Y6.1408 -G1 X2.3195 Y6.1804 -G2 X2.3002 Y6.1969 I0.0955 J0.1315 -G0 Z0.25 -G0 X2.3489 Y6.2209 -G1 Z-0.05 F30 -G2 X2.3025 Y6.3119 I0.0661 J0.091 F10 -G2 X2.303 Y6.3224 I0.1125 J0 -G2 X2.2672 Y6.3397 I0.0303 J0.1083 -G1 X2.1832 Y6.4007 -G1 X2.0993 Y6.3397 -G2 X2.0635 Y6.3224 I-0.0661 J0.091 -G2 X2.064 Y6.3119 I-0.112 J-0.0105 -G2 X2.0176 Y6.2209 I-0.1125 J0 -G1 X1.9336 Y6.1599 -G1 X1.9657 Y6.0612 -G2 X1.9713 Y6.0264 I-0.107 J-0.0348 -G2 X1.9711 Y6.0201 I-0.1125 J0 -G1 X2.0442 Y6.0201 -G1 X2.0762 Y6.1188 -G2 X2.2907 Y6.1173 I0.107 J-0.0347 -G1 X2.3208 Y6.0201 -G1 X2.3954 Y6.0201 -G2 X2.3952 Y6.0264 I0.1123 J0.0062 -G2 X2.4007 Y6.0612 I0.1125 J0 -G1 X2.4328 Y6.1599 -G1 X2.3489 Y6.2209 -G0 Z0.25 -G0 X2.2839 Y5.9701 -G1 Z-0.05 F30 -G1 X2.2429 Y6.1025 F10 -G3 X2.1238 Y6.1034 I-0.0597 J-0.0185 -G1 X2.0805 Y5.9701 -G1 X1.9403 Y5.9701 -G3 X1.8778 Y5.9076 I0 J-0.0625 -G3 X1.9036 Y5.857 I0.0625 J0 -G1 X2.017 Y5.7747 -G1 X1.9737 Y5.6414 -G3 X1.9706 Y5.6221 I0.0594 J-0.0193 -G3 X2.0699 Y5.5715 I0.0625 J0 -G1 X2.1832 Y5.6539 -G1 X2.2966 Y5.5715 -G3 X2.3958 Y5.6221 I0.0367 J0.0506 -G3 X2.3928 Y5.6414 I-0.0625 J0 -G1 X2.3495 Y5.7747 -G1 X2.4629 Y5.857 -G3 X2.4887 Y5.9076 I-0.0367 J0.0506 -G3 X2.4262 Y5.9701 I-0.0625 J0 -G1 X2.2839 Y5.9701 -G0 Z0.25 -G0 X2.5497 Y5.802 -G1 Z-0.05 F30 -G2 X2.7664 Y5.8016 I0.1081 J-0.1213 F10 -G2 X2.7287 Y5.8844 I0.1232 J0.106 -G2 X2.7124 Y5.8949 I0.0792 J0.1419 -G1 X2.6578 Y5.9346 -G1 X2.6032 Y5.8949 -G2 X2.587 Y5.8845 I-0.0955 J0.1315 -G2 X2.5497 Y5.802 I-0.1609 J0.0231 -G2 X2.5343 Y5.7863 I-0.1235 J0.1056 -G2 X2.5497 Y5.802 I0.1235 J-0.1056 -G0 Z0.25 -G0 X2.8486 Y5.7365 -G1 Z-0.05 F30 -G1 X2.7941 Y5.7761 F10 -G2 X2.781 Y5.7867 I0.0955 J0.1315 -G2 X2.8131 Y5.7287 I-0.1232 J-0.106 -G1 X2.8292 Y5.6767 -G1 X2.8486 Y5.7365 -G0 Z0.25 -G0 X2.9074 Y5.7556 -G1 Z-0.05 F30 -G1 X2.8235 Y5.8166 F10 -G2 X2.7771 Y5.9076 I0.0661 J0.091 -G2 X2.7776 Y5.918 I0.1125 J0 -G2 X2.7418 Y5.9353 I0.0303 J0.1083 -G1 X2.6578 Y5.9964 -G1 X2.5738 Y5.9353 -G2 X2.5382 Y5.9181 I-0.0661 J0.091 -G2 X2.5387 Y5.9076 I-0.112 J-0.0104 -G2 X2.4923 Y5.8166 I-0.1125 J0 -G1 X2.4083 Y5.7556 -G1 X2.4403 Y5.6568 -G2 X2.4458 Y5.6221 I-0.107 J-0.0347 -G2 X2.4457 Y5.6167 I-0.1125 J0 -G1 X2.5188 Y5.6167 -G1 X2.5508 Y5.7155 -G2 X2.7653 Y5.714 I0.107 J-0.0347 -G1 X2.7954 Y5.6167 -G1 X2.8699 Y5.6167 -G2 X2.8698 Y5.6221 I0.1124 J0.0054 -G2 X2.8753 Y5.6569 I0.1125 J0 -G1 X2.9074 Y5.7556 -G0 Z0.25 -G0 X2.7585 Y5.5667 -G1 Z-0.05 F30 -G1 X2.7175 Y5.6992 F10 -G3 X2.5984 Y5.7 I-0.0597 J-0.0185 -G1 X2.5551 Y5.5667 -G1 X2.415 Y5.5667 -G3 X2.3525 Y5.5042 I0 J-0.0625 -G3 X2.3783 Y5.4536 I0.0625 J0 -G1 X2.4916 Y5.3712 -G1 X2.4483 Y5.238 -G3 X2.4452 Y5.2186 I0.0594 J-0.0193 -G3 X2.5445 Y5.1681 I0.0625 J0 -G1 X2.6578 Y5.2505 -G1 X2.7712 Y5.1681 -G3 X2.8704 Y5.2186 I0.0367 J0.0506 -G3 X2.8674 Y5.2379 I-0.0625 J0 -G1 X2.8241 Y5.3712 -G1 X2.9375 Y5.4536 -G3 X2.9632 Y5.5042 I-0.0367 J0.0506 -G3 X2.9007 Y5.5667 I-0.0625 J0 -G1 X2.7585 Y5.5667 -G0 Z0.25 -G0 X2.9778 Y5.3257 -G1 Z-0.05 F30 -G2 X3.2876 Y5.3235 I0.1546 J-0.0502 F10 -G1 X3.3035 Y5.2722 -G1 X3.3233 Y5.333 -G1 X3.2687 Y5.3727 -G2 X3.2035 Y5.4802 I0.0955 J0.1315 -G2 X3.1871 Y5.4906 I0.0792 J0.1419 -G1 X3.1324 Y5.5303 -G1 X3.0778 Y5.4906 -G2 X3.0615 Y5.4802 I-0.0955 J0.1315 -G2 X2.9963 Y5.3727 I-0.1607 J0.024 -G1 X2.9416 Y5.333 -G1 X2.9609 Y5.2736 -G1 X2.9778 Y5.3257 -G1 X3.0254 Y5.3103 F10 -G2 X3.2399 Y5.3088 I0.107 J-0.0347 F10 -G1 X3.2699 Y5.2116 -G1 X3.3447 Y5.2116 -G2 X3.3445 Y5.2186 I0.1123 J0.0071 -G2 X3.35 Y5.2534 I0.1125 J0 -G1 X3.382 Y5.3521 -G1 X3.298 Y5.4132 -G2 X3.2517 Y5.5042 I0.0661 J0.091 -G2 X3.2521 Y5.5138 I0.1125 J0 -G2 X3.2165 Y5.531 I0.0305 J0.1083 -G1 X3.1324 Y5.5921 -G1 X3.0484 Y5.5311 -G2 X3.0128 Y5.5138 I-0.0661 J0.091 -G2 X3.0132 Y5.5042 I-0.1121 J-0.0096 -G2 X2.9669 Y5.4132 I-0.1125 J0 -G1 X2.8829 Y5.3521 -G1 X2.9149 Y5.2534 -G2 X2.9204 Y5.2186 I-0.107 J-0.0347 -G2 X2.9202 Y5.2116 I-0.1125 J0 -G1 X2.9934 Y5.2116 -G1 X3.0254 Y5.3103 -G0 Z0.25 -G0 X3.2331 Y5.1616 -G1 Z-0.05 F30 -G1 X3.1921 Y5.294 F10 -G3 X3.073 Y5.2948 I-0.0597 J-0.0185 -G1 X3.0297 Y5.1616 -G1 X2.8896 Y5.1616 -G3 X2.8271 Y5.0991 I0 J-0.0625 -G3 X2.8529 Y5.0485 I0.0625 J0 -G1 X2.9662 Y4.9661 -G1 X2.9229 Y4.8329 -G3 X2.9198 Y4.8135 I0.0594 J-0.0193 -G3 X3.019 Y4.763 I0.0625 J0 -G1 X3.1324 Y4.8454 -G1 X3.2459 Y4.763 -G3 X3.3451 Y4.8135 I0.0367 J0.0506 -G3 X3.342 Y4.8329 I-0.0625 J0 -G1 X3.2987 Y4.9661 -G1 X3.4121 Y5.0485 -G3 X3.4378 Y5.0991 I-0.0367 J0.0506 -G3 X3.3753 Y5.1616 I-0.0625 J0 -G1 X3.2331 Y5.1616 -G0 Z0.25 -G0 X3.4526 Y4.9214 -G1 Z-0.05 F30 -G2 X3.7218 Y4.9862 I0.1545 J-0.0503 F10 -G2 X3.6778 Y5.0769 I0.1169 J0.1129 -G2 X3.6617 Y5.0872 I0.0794 J0.1418 -G1 X3.6071 Y5.1268 -G1 X3.5525 Y5.0872 -G2 X3.5363 Y5.0768 I-0.0955 J0.1315 -G2 X3.4708 Y4.9676 I-0.161 J0.0223 -G1 X3.4163 Y4.928 -G1 X3.4355 Y4.8689 -G1 X3.4526 Y4.9214 -G0 Z0.25 -G0 X3.724 Y4.984 -G1 Z-0.05 F30 -G2 X3.7624 Y4.9191 I-0.1169 J-0.1129 F10 -G1 X3.7783 Y4.8676 -G1 X3.7979 Y4.9279 -G1 X3.7432 Y4.9676 -G2 X3.724 Y4.984 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.7726 Y5.008 -G1 Z-0.05 F30 -G2 X3.7263 Y5.0991 I0.0661 J0.091 F10 -G2 X3.7268 Y5.1103 I0.1125 J0 -G2 X3.6911 Y5.1276 I0.0304 J0.1083 -G1 X3.6071 Y5.1886 -G1 X3.5231 Y5.1276 -G2 X3.4873 Y5.1103 I-0.0661 J0.091 -G2 X3.4878 Y5.0991 I-0.1119 J-0.0112 -G2 X3.4414 Y5.008 I-0.1125 J0 -G1 X3.3575 Y4.947 -G1 X3.3896 Y4.8483 -G2 X3.3951 Y4.8135 I-0.107 J-0.0348 -G2 X3.3949 Y4.8072 I-0.1125 J0 -G1 X3.468 Y4.8072 -G1 X3.5001 Y4.9059 -G2 X3.7146 Y4.9043 I0.107 J-0.0348 -G1 X3.7446 Y4.8072 -G1 X3.8192 Y4.8072 -G2 X3.8191 Y4.8135 I0.1123 J0.0064 -G2 X3.8246 Y4.8483 I0.1125 J0 -G1 X3.8566 Y4.947 -G1 X3.7726 Y5.008 -G0 Z0.25 -G0 X3.7077 Y4.7572 -G1 Z-0.05 F30 -G1 X3.6668 Y4.8896 F10 -G3 X3.5477 Y4.8905 I-0.0597 J-0.0184 -G1 X3.5043 Y4.7572 -G1 X3.3642 Y4.7572 -G3 X3.3017 Y4.6947 I0 J-0.0625 -G3 X3.3274 Y4.6441 I0.0625 J0 -G1 X3.4408 Y4.5617 -G1 X3.3975 Y4.4285 -G3 X3.3945 Y4.4092 I0.0594 J-0.0193 -G3 X3.4937 Y4.3586 I0.0625 J0 -G1 X3.6071 Y4.441 -G1 X3.7205 Y4.3586 -G3 X3.8197 Y4.4092 I0.0367 J0.0506 -G3 X3.8166 Y4.4285 I-0.0625 J0 -G1 X3.7733 Y4.5618 -G1 X3.8866 Y4.6441 -G3 X3.9124 Y4.6947 I-0.0367 J0.0506 -G3 X3.8499 Y4.7572 I-0.0625 J0 -G1 X3.7077 Y4.7572 -G0 Z0.25 -G0 X3.9668 Y4.5818 -G1 Z-0.05 F30 -G2 X4.1965 Y4.5818 I0.1148 J-0.115 F10 -G2 X4.1526 Y4.6716 I0.1169 J0.1129 -G2 X4.1363 Y4.6821 I0.0792 J0.1419 -G1 X4.0817 Y4.7217 -G1 X4.0271 Y4.6821 -G2 X4.0108 Y4.6716 I-0.0955 J0.1315 -G2 X3.9668 Y4.5818 I-0.1609 J0.023 -G2 X3.9648 Y4.5797 I-0.1169 J0.1129 -G2 X3.9668 Y4.5818 I0.1169 J-0.1129 -G0 Z0.25 -G0 X4.1986 Y4.5797 -G1 Z-0.05 F30 -G2 X4.2369 Y4.5149 I-0.1169 J-0.1129 F10 -G1 X4.2529 Y4.4633 -G1 X4.2725 Y4.5236 -G1 X4.2179 Y4.5632 -G2 X4.1986 Y4.5797 I0.0955 J0.1315 -G0 Z0.25 -G0 X4.2473 Y4.6037 -G1 Z-0.05 F30 -G2 X4.2009 Y4.6947 I0.0661 J0.091 F10 -G2 X4.2014 Y4.7052 I0.1125 J0 -G2 X4.1656 Y4.7225 I0.0303 J0.1083 -G1 X4.0817 Y4.7835 -G1 X3.9977 Y4.7225 -G2 X3.9619 Y4.7052 I-0.0661 J0.091 -G2 X3.9624 Y4.6947 I-0.112 J-0.0105 -G2 X3.916 Y4.6037 I-0.1125 J0 -G1 X3.8321 Y4.5427 -G1 X3.8642 Y4.444 -G2 X3.8697 Y4.4092 I-0.107 J-0.0348 -G2 X3.8695 Y4.4029 I-0.1125 J0 -G1 X3.9426 Y4.4029 -G1 X3.9747 Y4.5016 -G2 X4.1891 Y4.5001 I0.107 J-0.0347 -G1 X4.2192 Y4.4029 -G1 X4.2938 Y4.4029 -G2 X4.2937 Y4.4092 I0.1123 J0.0062 -G2 X4.2992 Y4.444 I0.1125 J0 -G1 X4.3313 Y4.5427 -G1 X4.2473 Y4.6037 -G0 Z0.25 -G0 X4.1823 Y4.3529 -G1 Z-0.05 F30 -G1 X4.1414 Y4.4853 F10 -G3 X4.0222 Y4.4862 I-0.0597 J-0.0185 -G1 X3.979 Y4.3529 -G1 X3.8388 Y4.3529 -G3 X3.7763 Y4.2904 I0 J-0.0625 -G3 X3.802 Y4.2399 I0.0625 J0 -G1 X3.9154 Y4.1575 -G1 X3.8721 Y4.0242 -G3 X3.8691 Y4.0049 I0.0594 J-0.0193 -G3 X3.9683 Y3.9543 I0.0625 J0 -G1 X4.0817 Y4.0367 -G1 X4.195 Y3.9543 -G3 X4.2943 Y4.0049 I0.0367 J0.0506 -G3 X4.2912 Y4.0242 I-0.0625 J0 -G1 X4.248 Y4.1575 -G1 X4.3613 Y4.2399 -G3 X4.3871 Y4.2904 I-0.0367 J0.0506 -G3 X4.3246 Y4.3529 I-0.0625 J0 -G1 X4.1823 Y4.3529 -G0 Z0.25 -G0 X4.4431 Y4.1792 -G1 Z-0.05 F30 -G2 X4.6711 Y4.1776 I0.1132 J-0.1166 F10 -G2 X4.6272 Y4.2673 I0.1169 J0.1129 -G2 X4.6108 Y4.2777 I0.0792 J0.1419 -G1 X4.5563 Y4.3174 -G1 X4.5017 Y4.2777 -G2 X4.4854 Y4.2673 I-0.0955 J0.1315 -G2 X4.4431 Y4.1792 I-0.1609 J0.0231 -G2 X4.4378 Y4.1738 I-0.1185 J0.1112 -G2 X4.4431 Y4.1792 I0.1185 J-0.1112 -G0 Z0.25 -G0 X4.6732 Y4.1755 -G1 Z-0.05 F30 -G2 X4.7115 Y4.1106 I-0.1169 J-0.1129 F10 -G1 X4.7275 Y4.059 -G1 X4.7471 Y4.1193 -G1 X4.6925 Y4.159 -G2 X4.6732 Y4.1755 I0.0955 J0.1315 -G0 Z0.25 -G0 X4.7219 Y4.1994 -G1 Z-0.05 F30 -G2 X4.6755 Y4.2904 I0.0661 J0.091 F10 -G2 X4.676 Y4.3008 I0.1125 J0 -G2 X4.6402 Y4.3182 I0.0303 J0.1083 -G1 X4.5563 Y4.3792 -G1 X4.4723 Y4.3182 -G2 X4.4366 Y4.3009 I-0.0661 J0.091 -G2 X4.4371 Y4.2904 I-0.112 J-0.0104 -G2 X4.3907 Y4.1994 I-0.1125 J0 -G1 X4.3067 Y4.1384 -G1 X4.3388 Y4.0396 -G2 X4.3443 Y4.0049 I-0.107 J-0.0347 -G2 X4.3441 Y3.9986 I-0.1125 J0 -G1 X4.4172 Y3.9986 -G1 X4.4493 Y4.0973 -G2 X4.6637 Y4.0958 I0.107 J-0.0347 -G1 X4.6938 Y3.9986 -G1 X4.7684 Y3.9986 -G2 X4.7682 Y4.0049 I0.1123 J0.0062 -G2 X4.7738 Y4.0397 I0.1125 J0 -G1 X4.8059 Y4.1384 -G1 X4.7219 Y4.1994 -G0 Z0.25 -G0 X5.1315 Y4.3529 -G1 Z-0.05 F30 -G1 X5.0905 Y4.4853 F10 -G3 X4.9714 Y4.4862 I-0.0597 J-0.0185 -G1 X4.9281 Y4.3529 -G1 X4.788 Y4.3529 -G3 X4.7255 Y4.2904 I0 J-0.0625 -G3 X4.7513 Y4.2399 I0.0625 J0 -G1 X4.8646 Y4.1575 -G1 X4.8213 Y4.0242 -G3 X4.8182 Y4.0049 I0.0594 J-0.0193 -G3 X4.9175 Y3.9543 I0.0625 J0 -G1 X5.0309 Y4.0367 -G1 X5.1443 Y3.9543 -G3 X5.2435 Y4.0049 I0.0367 J0.0506 -G3 X5.2405 Y4.0242 I-0.0625 J0 -G1 X5.1971 Y4.1575 -G1 X5.3105 Y4.2399 -G3 X5.3363 Y4.2904 I-0.0367 J0.0506 -G3 X5.2738 Y4.3529 I-0.0625 J0 -G1 X5.1315 Y4.3529 -G0 Z0.25 -G0 X5.1478 Y4.5797 -G1 Z-0.05 F30 -G2 X5.1861 Y4.5149 I-0.1169 J-0.1129 F10 -G1 X5.2021 Y4.4631 -G1 X5.2217 Y4.5235 -G1 X5.1671 Y4.5632 -G2 X5.1478 Y4.5797 I0.0955 J0.1315 -G0 Z0.25 -G0 X5.1965 Y4.6037 -G1 Z-0.05 F30 -G2 X5.1501 Y4.6947 I0.0661 J0.091 F10 -G2 X5.1506 Y4.7052 I0.1125 J0 -G2 X5.115 Y4.7225 I0.0304 J0.1083 -G1 X5.0309 Y4.7836 -G1 X4.9469 Y4.7225 -G2 X4.9112 Y4.7052 I-0.0661 J0.091 -G2 X4.9117 Y4.6947 I-0.112 J-0.0106 -G2 X4.8653 Y4.6037 I-0.1125 J0 -G1 X4.7813 Y4.5426 -G1 X4.8134 Y4.4439 -G2 X4.8189 Y4.4092 I-0.107 J-0.0347 -G2 X4.8187 Y4.4029 I-0.1125 J0 -G1 X4.8918 Y4.4029 -G1 X4.9238 Y4.5016 -G2 X5.1383 Y4.5001 I0.107 J-0.0347 -G1 X5.1684 Y4.4029 -G1 X5.2431 Y4.4029 -G2 X5.2429 Y4.4092 I0.1123 J0.0062 -G2 X5.2484 Y4.4439 I0.1125 J0 -G1 X5.2805 Y4.5426 -G1 X5.1965 Y4.6037 -G0 Z0.25 -G0 X4.9177 Y4.5835 -G1 Z-0.05 F30 -G2 X5.1457 Y4.5818 I0.1132 J-0.1166 F10 -G2 X5.1017 Y4.6717 I0.1169 J0.1129 -G2 X5.0856 Y4.682 I0.0793 J0.1418 -G1 X5.0309 Y4.7218 -G1 X4.9763 Y4.6821 -G2 X4.96 Y4.6717 I-0.0955 J0.1315 -G2 X4.9177 Y4.5835 I-0.1609 J0.023 -G2 X4.9124 Y4.5781 I-0.1185 J0.1112 -G2 X4.9177 Y4.5835 I0.1185 J-0.1112 -G0 Z0.25 -G0 X4.6569 Y4.7572 -G1 Z-0.05 F30 -G1 X4.616 Y4.8896 F10 -G3 X4.4968 Y4.8904 I-0.0597 J-0.0185 -G1 X4.4535 Y4.7572 -G1 X4.3134 Y4.7572 -G3 X4.2509 Y4.6947 I0 J-0.0625 -G3 X4.2767 Y4.6441 I0.0625 J0 -G1 X4.3901 Y4.5618 -G1 X4.3467 Y4.4285 -G3 X4.3437 Y4.4092 I0.0594 J-0.0193 -G3 X4.4429 Y4.3586 I0.0625 J0 -G1 X4.5563 Y4.441 -G1 X4.6696 Y4.3586 -G3 X4.7689 Y4.4092 I0.0367 J0.0506 -G3 X4.7658 Y4.4285 I-0.0625 J0 -G1 X4.7225 Y4.5617 -G1 X4.8359 Y4.6441 -G3 X4.8617 Y4.6947 I-0.0367 J0.0506 -G3 X4.7992 Y4.7572 I-0.0625 J0 -G1 X4.6569 Y4.7572 -G0 Z0.25 -G0 X4.4415 Y4.9862 -G1 Z-0.05 F30 -G2 X4.7115 Y4.9192 I0.1147 J-0.1151 F10 -G1 X4.7274 Y4.8676 -G1 X4.7471 Y4.928 -G1 X4.6925 Y4.9676 -G2 X4.6271 Y5.0768 I0.0955 J0.1315 -G2 X4.6108 Y5.0872 I0.0793 J0.1418 -G1 X4.5563 Y5.1268 -G1 X4.5017 Y5.0872 -G2 X4.4856 Y5.0769 I-0.0955 J0.1315 -G2 X4.4415 Y4.9862 I-0.161 J0.0222 -G2 X4.4393 Y4.984 I-0.1169 J0.1129 -G2 X4.4415 Y4.9862 I0.1169 J-0.1129 -G1 X4.3907 Y5.008 F10 -G1 X4.3067 Y4.947 F10 -G1 X4.3388 Y4.8483 -G2 X4.3443 Y4.8135 I-0.107 J-0.0347 -G2 X4.3441 Y4.8072 I-0.1125 J0 -G1 X4.4172 Y4.8072 -G1 X4.4493 Y4.9059 -G2 X4.6637 Y4.9044 I0.107 J-0.0347 -G1 X4.6938 Y4.8072 -G1 X4.7684 Y4.8072 -G2 X4.7682 Y4.8135 I0.1123 J0.0064 -G2 X4.7738 Y4.8483 I0.1125 J0 -G1 X4.8059 Y4.947 -G1 X4.7219 Y5.008 -G2 X4.6755 Y5.0991 I0.0661 J0.091 -G2 X4.6761 Y5.1103 I0.1125 J0 -G2 X4.6402 Y5.1276 I0.0303 J0.1084 -G1 X4.5563 Y5.1886 -G1 X4.4723 Y5.1276 -G2 X4.4365 Y5.1103 I-0.0661 J0.091 -G2 X4.4371 Y5.0991 I-0.1119 J-0.0113 -G2 X4.3907 Y5.008 I-0.1125 J0 -G0 Z0.25 -G0 X4.1823 Y5.1616 -G1 Z-0.05 F30 -G1 X4.1414 Y5.294 F10 -G3 X4.0222 Y5.2948 I-0.0597 J-0.0185 -G1 X3.979 Y5.1616 -G1 X3.8388 Y5.1616 -G3 X3.7763 Y5.0991 I0 J-0.0625 -G3 X3.802 Y5.0485 I0.0625 J0 -G1 X3.9154 Y4.9661 -G1 X3.8721 Y4.8328 -G3 X3.8691 Y4.8135 I0.0594 J-0.0193 -G3 X3.9683 Y4.763 I0.0625 J0 -G1 X4.0817 Y4.8453 -G1 X4.195 Y4.763 -G3 X4.2943 Y4.8135 I0.0367 J0.0506 -G3 X4.2912 Y4.8328 I-0.0625 J0 -G1 X4.248 Y4.9661 -G1 X4.3613 Y5.0485 -G3 X4.3871 Y5.0991 I-0.0367 J0.0506 -G3 X4.3246 Y5.1616 I-0.0625 J0 -G1 X4.1823 Y5.1616 -G0 Z0.25 -G0 X3.9271 Y5.3257 -G1 Z-0.05 F30 -G2 X4.2369 Y5.3235 I0.1546 J-0.0502 F10 -G1 X4.2527 Y5.2724 -G1 X4.2725 Y5.3331 -G1 X4.2179 Y5.3727 -G2 X4.1527 Y5.4801 I0.0955 J0.1315 -G2 X4.1363 Y5.4906 I0.079 J0.142 -G1 X4.0817 Y5.5303 -G1 X4.0271 Y5.4906 -G2 X4.0106 Y5.4801 I-0.0955 J0.1315 -G2 X3.9454 Y5.3727 I-0.1607 J0.0241 -G1 X3.8909 Y5.3331 -G1 X3.9102 Y5.2736 -G1 X3.9271 Y5.3257 -G1 X3.9747 Y5.3103 F10 -G2 X4.1891 Y5.3088 I0.107 J-0.0347 F10 -G1 X4.2192 Y5.2116 -G1 X4.2939 Y5.2116 -G2 X4.2937 Y5.2186 I0.1123 J0.0071 -G2 X4.2992 Y5.2534 I0.1125 J0 -G1 X4.3313 Y5.3521 -G1 X4.2473 Y5.4132 -G2 X4.2009 Y5.5042 I0.0661 J0.091 -G2 X4.2014 Y5.5138 I0.1125 J0 -G2 X4.1656 Y5.5311 I0.0304 J0.1083 -G1 X4.0817 Y5.5921 -G1 X3.9977 Y5.5311 -G2 X3.962 Y5.5138 I-0.0661 J0.091 -G2 X3.9624 Y5.5042 I-0.1121 J-0.0096 -G2 X3.916 Y5.4132 I-0.1125 J0 -G1 X3.8321 Y5.3521 -G1 X3.8642 Y5.2534 -G2 X3.8697 Y5.2186 I-0.107 J-0.0348 -G2 X3.8695 Y5.2116 I-0.1125 J0 -G1 X3.9426 Y5.2116 -G1 X3.9747 Y5.3103 -G0 Z0.25 -G0 X3.7077 Y5.5667 -G1 Z-0.05 F30 -G1 X3.6668 Y5.6992 F10 -G3 X3.5477 Y5.7001 I-0.0597 J-0.0184 -G1 X3.5043 Y5.5667 -G1 X3.3642 Y5.5667 -G3 X3.3017 Y5.5042 I0 J-0.0625 -G3 X3.3274 Y5.4536 I0.0625 J0 -G1 X3.4408 Y5.3712 -G1 X3.3975 Y5.2379 -G3 X3.3945 Y5.2186 I0.0594 J-0.0193 -G3 X3.4937 Y5.1681 I0.0625 J0 -G1 X3.6071 Y5.2505 -G1 X3.7205 Y5.1681 -G3 X3.8197 Y5.2186 I0.0367 J0.0506 -G3 X3.8166 Y5.238 I-0.0625 J0 -G1 X3.7733 Y5.3712 -G1 X3.8866 Y5.4536 -G3 X3.9124 Y5.5042 I-0.0367 J0.0506 -G3 X3.8499 Y5.5667 I-0.0625 J0 -G1 X3.7077 Y5.5667 -G0 Z0.25 -G0 X3.7979 Y5.7365 -G1 Z-0.05 F30 -G1 X3.7432 Y5.7761 F10 -G2 X3.7306 Y5.7863 I0.0955 J0.1315 -G2 X3.7624 Y5.7286 I-0.1235 J-0.1056 -G1 X3.7784 Y5.6766 -G1 X3.7979 Y5.7365 -G0 Z0.25 -G0 X3.8566 Y5.7556 -G1 Z-0.05 F30 -G1 X3.7726 Y5.8166 F10 -G2 X3.7263 Y5.9076 I0.0661 J0.091 -G2 X3.7267 Y5.9181 I0.1125 J0 -G2 X3.6911 Y5.9353 I0.0305 J0.1083 -G1 X3.6071 Y5.9964 -G1 X3.5231 Y5.9353 -G2 X3.4873 Y5.918 I-0.0661 J0.091 -G2 X3.4878 Y5.9076 I-0.112 J-0.0104 -G2 X3.4414 Y5.8166 I-0.1125 J0 -G1 X3.3575 Y5.7556 -G1 X3.3896 Y5.6569 -G2 X3.3951 Y5.6221 I-0.107 J-0.0348 -G2 X3.395 Y5.6167 I-0.1125 J0 -G1 X3.468 Y5.6167 -G1 X3.5001 Y5.7155 -G2 X3.7146 Y5.7139 I0.107 J-0.0348 -G1 X3.7446 Y5.6167 -G1 X3.8192 Y5.6167 -G2 X3.8191 Y5.6221 I0.1124 J0.0054 -G2 X3.8246 Y5.6568 I0.1125 J0 -G1 X3.8566 Y5.7556 -G0 Z0.25 -G0 X3.4985 Y5.8016 -G1 Z-0.05 F30 -G2 X3.7152 Y5.802 I0.1086 J-0.1209 F10 -G2 X3.6779 Y5.8845 I0.1235 J0.1056 -G2 X3.6617 Y5.8949 I0.0793 J0.1418 -G1 X3.6071 Y5.9346 -G1 X3.5525 Y5.8949 -G2 X3.5362 Y5.8844 I-0.0955 J0.1315 -G2 X3.4985 Y5.8016 I-0.1608 J0.0232 -G2 X3.4839 Y5.7867 I-0.1232 J0.106 -G2 X3.4985 Y5.8016 I0.1232 J-0.106 -G0 Z0.25 -G0 X3.2331 Y5.9701 -G1 Z-0.05 F30 -G1 X3.1921 Y6.1025 F10 -G3 X3.073 Y6.1034 I-0.0597 J-0.0185 -G1 X3.0297 Y5.9701 -G1 X2.8896 Y5.9701 -G3 X2.8271 Y5.9076 I0 J-0.0625 -G3 X2.8529 Y5.857 I0.0625 J0 -G1 X2.9662 Y5.7747 -G1 X2.9229 Y5.6414 -G3 X2.9198 Y5.6221 I0.0594 J-0.0193 -G3 X3.019 Y5.5715 I0.0625 J0 -G1 X3.1324 Y5.6539 -G1 X3.2459 Y5.5715 -G3 X3.3451 Y5.6221 I0.0367 J0.0506 -G3 X3.342 Y5.6414 I-0.0625 J0 -G1 X3.2987 Y5.7747 -G1 X3.4121 Y5.857 -G3 X3.4378 Y5.9076 I-0.0367 J0.0506 -G3 X3.3753 Y5.9701 I-0.0625 J0 -G1 X3.2331 Y5.9701 -G0 Z0.25 -G0 X3.2493 Y6.1969 -G1 Z-0.05 F30 -G2 X3.2876 Y6.1321 I-0.1169 J-0.1129 F10 -G1 X3.3037 Y6.0803 -G1 X3.3233 Y6.1407 -G1 X3.2687 Y6.1804 -G2 X3.2493 Y6.1969 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.298 Y6.2209 -G1 Z-0.05 F30 -G2 X3.2517 Y6.3119 I0.0661 J0.091 F10 -G2 X3.2522 Y6.3224 I0.1125 J0 -G2 X3.2165 Y6.3397 I0.0304 J0.1083 -G1 X3.1324 Y6.4007 -G1 X3.0484 Y6.3397 -G2 X3.0127 Y6.3224 I-0.0661 J0.091 -G2 X3.0132 Y6.3119 I-0.112 J-0.0106 -G2 X2.9669 Y6.2209 I-0.1125 J0 -G1 X2.8829 Y6.1598 -G1 X2.9149 Y6.0611 -G2 X2.9204 Y6.0264 I-0.107 J-0.0347 -G2 X2.9202 Y6.0201 I-0.1125 J0 -G1 X2.9934 Y6.0201 -G1 X3.0254 Y6.1188 -G2 X3.2399 Y6.1173 I0.107 J-0.0347 -G1 X3.2699 Y6.0201 -G1 X3.3447 Y6.0201 -G2 X3.3445 Y6.0264 I0.1123 J0.0062 -G2 X3.35 Y6.0611 I0.1125 J0 -G1 X3.382 Y6.1598 -G1 X3.298 Y6.2209 -G0 Z0.25 -G0 X3.0192 Y6.2007 -G1 Z-0.05 F30 -G2 X3.2473 Y6.199 I0.1132 J-0.1166 F10 -G2 X3.2033 Y6.2889 I0.1169 J0.1129 -G2 X3.1871 Y6.2992 I0.0793 J0.1418 -G1 X3.1324 Y6.339 -G1 X3.0778 Y6.2993 -G2 X3.0616 Y6.2889 I-0.0955 J0.1315 -G2 X3.0192 Y6.2007 I-0.1609 J0.023 -G2 X3.0139 Y6.1953 I-0.1185 J0.1112 -G2 X3.0192 Y6.2007 I0.1185 J-0.1112 -G0 Z0.25 -G0 X2.7585 Y6.3744 -G1 Z-0.05 F30 -G1 X2.7175 Y6.5068 F10 -G3 X2.5984 Y6.5076 I-0.0597 J-0.0185 -G1 X2.5551 Y6.3744 -G1 X2.415 Y6.3744 -G3 X2.3525 Y6.3119 I0 J-0.0625 -G3 X2.3783 Y6.2613 I0.0625 J0 -G1 X2.4916 Y6.1789 -G1 X2.4483 Y6.0457 -G3 X2.4452 Y6.0264 I0.0594 J-0.0193 -G3 X2.5445 Y5.9758 I0.0625 J0 -G1 X2.6578 Y6.0582 -G1 X2.7712 Y5.9758 -G3 X2.8704 Y6.0264 I0.0367 J0.0506 -G3 X2.8674 Y6.0457 I-0.0625 J0 -G1 X2.8241 Y6.1789 -G1 X2.9375 Y6.2613 -G3 X2.9632 Y6.3119 I-0.0367 J0.0506 -G3 X2.9007 Y6.3744 I-0.0625 J0 -G1 X2.7585 Y6.3744 -G0 Z0.25 -G0 X2.5431 Y6.6034 -G1 Z-0.05 F30 -G2 X2.8131 Y6.5364 I0.1147 J-0.1151 F10 -G1 X2.829 Y6.4848 -G1 X2.8486 Y6.5451 -G1 X2.7941 Y6.5848 -G2 X2.7286 Y6.694 I0.0955 J0.1315 -G2 X2.7124 Y6.7044 I0.0793 J0.1418 -G1 X2.6578 Y6.744 -G1 X2.6032 Y6.7044 -G2 X2.5871 Y6.6941 I-0.0955 J0.1315 -G2 X2.5431 Y6.6034 I-0.161 J0.0222 -G2 X2.5409 Y6.6012 I-0.1169 J0.1129 -G2 X2.5431 Y6.6034 I0.1169 J-0.1129 -G1 X2.4923 Y6.6252 F10 -G1 X2.4083 Y6.5642 F10 -G1 X2.4403 Y6.4655 -G2 X2.4458 Y6.4307 I-0.107 J-0.0347 -G2 X2.4457 Y6.4244 I-0.1125 J0 -G1 X2.5188 Y6.4244 -G1 X2.5508 Y6.5231 -G2 X2.7653 Y6.5216 I0.107 J-0.0347 -G1 X2.7954 Y6.4244 -G1 X2.87 Y6.4244 -G2 X2.8698 Y6.4307 I0.1123 J0.0064 -G2 X2.8753 Y6.4655 I0.1125 J0 -G1 X2.9074 Y6.5642 -G1 X2.8235 Y6.6252 -G2 X2.7771 Y6.7162 I0.0661 J0.091 -G2 X2.7777 Y6.7275 I0.1125 J0 -G2 X2.7418 Y6.7448 I0.0303 J0.1084 -G1 X2.6578 Y6.8058 -G1 X2.5738 Y6.7448 -G2 X2.5381 Y6.7275 I-0.0661 J0.091 -G2 X2.5387 Y6.7162 I-0.1119 J-0.0113 -G2 X2.4923 Y6.6252 I-0.1125 J0 -G0 Z0.25 -G0 X2.2839 Y6.7787 -G1 Z-0.05 F30 -G1 X2.2429 Y6.9112 F10 -G3 X2.1238 Y6.912 I-0.0597 J-0.0185 -G1 X2.0805 Y6.7787 -G1 X1.9403 Y6.7787 -G3 X1.8778 Y6.7162 I0 J-0.0625 -G3 X1.9036 Y6.6657 I0.0625 J0 -G1 X2.017 Y6.5833 -G1 X1.9737 Y6.45 -G3 X1.9706 Y6.4307 I0.0594 J-0.0193 -G3 X2.0699 Y6.3802 I0.0625 J0 -G1 X2.1832 Y6.4625 -G1 X2.2966 Y6.3802 -G3 X2.3958 Y6.4307 I0.0367 J0.0506 -G3 X2.3928 Y6.45 I-0.0625 J0 -G1 X2.3495 Y6.5833 -G1 X2.4629 Y6.6657 -G3 X2.4887 Y6.7162 I-0.0367 J0.0506 -G3 X2.4262 Y6.7787 I-0.0625 J0 -G1 X2.2839 Y6.7787 -G0 Z0.25 -G0 X2.2076 Y7.1674 -G1 Z-0.05 F30 -G1 X2.1589 Y7.1674 F10 -G2 X2.164 Y7.1214 I-0.2075 J-0.046 -G2 X2.1633 Y7.1043 I-0.2125 J0 -G2 X2.2032 Y7.1043 I0.02 J-0.2116 -G2 X2.2025 Y7.1214 I0.2118 J0.0171 -G2 X2.2076 Y7.1674 I0.2125 J0 -G1 X2.2525 Y7.1214 F10 -G2 X2.2839 Y7.2174 I0.1625 J0 F10 -G1 X2.0825 Y7.2174 -G2 X2.114 Y7.1214 I-0.1311 J-0.096 -G2 X2.047 Y6.9899 I-0.1625 J0 -G1 X1.9924 Y6.9502 -G1 X2.0118 Y6.8908 -G1 X2.0287 Y6.9429 -G2 X2.3385 Y6.9407 I0.1546 J-0.0502 -G1 X2.3543 Y6.8896 -G1 X2.3741 Y6.9502 -G1 X2.3195 Y6.9899 -G2 X2.2525 Y7.1214 I0.0955 J0.1315 -G1 X2.3025 Y7.1214 F10 -G2 X2.415 Y7.2339 I0.1125 J0 F10 -G1 X2.5188 Y7.2339 -G1 X2.5296 Y7.2674 -G1 X1.8358 Y7.2674 -G1 X1.8462 Y7.2339 -G1 X1.9515 Y7.2339 -G2 X2.064 Y7.1214 I0 J-0.1125 -G2 X2.0176 Y7.0303 I-0.1125 J0 -G1 X1.9336 Y6.9693 -G1 X1.9657 Y6.8706 -G2 X1.9713 Y6.8358 I-0.107 J-0.0348 -G2 X1.971 Y6.8287 I-0.1125 J0 -G1 X2.0442 Y6.8287 -G1 X2.0762 Y6.9274 -G2 X2.2907 Y6.926 I0.107 J-0.0347 -G1 X2.3208 Y6.8287 -G1 X2.3954 Y6.8287 -G2 X2.3952 Y6.8358 I0.1123 J0.0071 -G2 X2.4007 Y6.8706 I0.1125 J0 -G1 X2.4328 Y6.9693 -G1 X2.3489 Y7.0303 -G2 X2.3025 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X3.1567 Y7.1674 -G1 Z-0.05 F30 -G1 X3.1082 Y7.1674 F10 -G2 X3.1132 Y7.1214 I-0.2075 J-0.046 -G2 X3.1125 Y7.1043 I-0.2125 J0 -G2 X3.1524 Y7.1043 I0.0199 J-0.2116 -G2 X3.1517 Y7.1214 I0.2118 J0.0171 -G2 X3.1567 Y7.1674 I0.2125 J0 -G1 X3.2017 Y7.1214 F10 -G2 X3.2331 Y7.2174 I0.1625 J0 F10 -G1 X3.0318 Y7.2174 -G2 X3.0632 Y7.1214 I-0.1311 J-0.096 -G2 X2.9963 Y6.9899 I-0.1625 J0 -G1 X2.9416 Y6.9502 -G1 X2.9609 Y6.8908 -G1 X2.9778 Y6.9429 -G2 X3.2876 Y6.9407 I0.1546 J-0.0502 -G1 X3.3035 Y6.8894 -G1 X3.3233 Y6.9502 -G1 X3.2687 Y6.9899 -G2 X3.2017 Y7.1214 I0.0955 J0.1315 -G1 X3.2517 Y7.1214 F10 -G2 X3.3642 Y7.2339 I0.1125 J0 F10 -G1 X3.468 Y7.2339 -G1 X3.4789 Y7.2674 -G1 X2.785 Y7.2674 -G1 X2.7954 Y7.2339 -G1 X2.9007 Y7.2339 -G2 X3.0132 Y7.1214 I0 J-0.1125 -G2 X2.9669 Y7.0303 I-0.1125 J0 -G1 X2.8829 Y6.9693 -G1 X2.9149 Y6.8706 -G2 X2.9204 Y6.8358 I-0.107 J-0.0347 -G2 X2.9202 Y6.8287 I-0.1125 J0 -G1 X2.9934 Y6.8287 -G1 X3.0254 Y6.9274 -G2 X3.2399 Y6.926 I0.107 J-0.0347 -G1 X3.2699 Y6.8287 -G1 X3.3447 Y6.8287 -G2 X3.3445 Y6.8358 I0.1123 J0.0071 -G2 X3.35 Y6.8706 I0.1125 J0 -G1 X3.382 Y6.9693 -G1 X3.298 Y7.0303 -G2 X3.2517 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X3.2331 Y6.7787 -G1 Z-0.05 F30 -G1 X3.1921 Y6.9112 F10 -G3 X3.073 Y6.912 I-0.0597 J-0.0185 -G1 X3.0297 Y6.7787 -G1 X2.8896 Y6.7787 -G3 X2.8271 Y6.7162 I0 J-0.0625 -G3 X2.8529 Y6.6657 I0.0625 J0 -G1 X2.9662 Y6.5833 -G1 X2.9229 Y6.4501 -G3 X2.9198 Y6.4307 I0.0594 J-0.0193 -G3 X3.019 Y6.3802 I0.0625 J0 -G1 X3.1324 Y6.4625 -G1 X3.2459 Y6.3802 -G3 X3.3451 Y6.4307 I0.0367 J0.0506 -G3 X3.342 Y6.4501 I-0.0625 J0 -G1 X3.2987 Y6.5833 -G1 X3.4121 Y6.6657 -G3 X3.4378 Y6.7162 I-0.0367 J0.0506 -G3 X3.3753 Y6.7787 I-0.0625 J0 -G1 X3.2331 Y6.7787 -G0 Z0.25 -G0 X3.4526 Y6.5386 -G1 Z-0.05 F30 -G2 X3.7218 Y6.6034 I0.1545 J-0.0503 F10 -G2 X3.6778 Y6.6941 I0.1169 J0.1129 -G2 X3.6617 Y6.7044 I0.0794 J0.1418 -G1 X3.6071 Y6.744 -G1 X3.5525 Y6.7044 -G2 X3.5363 Y6.694 I-0.0955 J0.1315 -G2 X3.4708 Y6.5848 I-0.161 J0.0223 -G1 X3.4163 Y6.5451 -G1 X3.4355 Y6.4861 -G1 X3.4526 Y6.5386 -G0 Z0.25 -G0 X3.724 Y6.6012 -G1 Z-0.05 F30 -G2 X3.7624 Y6.5363 I-0.1169 J-0.1129 F10 -G1 X3.7783 Y6.4848 -G1 X3.7979 Y6.5451 -G1 X3.7432 Y6.5848 -G2 X3.724 Y6.6012 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.7726 Y6.6252 -G1 Z-0.05 F30 -G2 X3.7263 Y6.7162 I0.0661 J0.091 F10 -G2 X3.7268 Y6.7275 I0.1125 J0 -G2 X3.6911 Y6.7448 I0.0304 J0.1083 -G1 X3.6071 Y6.8058 -G1 X3.5231 Y6.7448 -G2 X3.4873 Y6.7275 I-0.0661 J0.091 -G2 X3.4878 Y6.7162 I-0.1119 J-0.0112 -G2 X3.4414 Y6.6252 I-0.1125 J0 -G1 X3.3575 Y6.5642 -G1 X3.3896 Y6.4655 -G2 X3.3951 Y6.4307 I-0.107 J-0.0348 -G2 X3.3949 Y6.4244 I-0.1125 J0 -G1 X3.468 Y6.4244 -G1 X3.5001 Y6.5231 -G2 X3.7146 Y6.5215 I0.107 J-0.0348 -G1 X3.7446 Y6.4244 -G1 X3.8192 Y6.4244 -G2 X3.8191 Y6.4307 I0.1123 J0.0064 -G2 X3.8246 Y6.4655 I0.1125 J0 -G1 X3.8566 Y6.5642 -G1 X3.7726 Y6.6252 -G0 Z0.25 -G0 X3.7077 Y6.3744 -G1 Z-0.05 F30 -G1 X3.6668 Y6.5068 F10 -G3 X3.5477 Y6.5077 I-0.0597 J-0.0184 -G1 X3.5043 Y6.3744 -G1 X3.3642 Y6.3744 -G3 X3.3017 Y6.3119 I0 J-0.0625 -G3 X3.3274 Y6.2613 I0.0625 J0 -G1 X3.4408 Y6.1789 -G1 X3.3975 Y6.0457 -G3 X3.3945 Y6.0264 I0.0594 J-0.0193 -G3 X3.4937 Y5.9758 I0.0625 J0 -G1 X3.6071 Y6.0582 -G1 X3.7205 Y5.9758 -G3 X3.8197 Y6.0264 I0.0367 J0.0506 -G3 X3.8166 Y6.0457 I-0.0625 J0 -G1 X3.7733 Y6.1789 -G1 X3.8866 Y6.2613 -G3 X3.9124 Y6.3119 I-0.0367 J0.0506 -G3 X3.8499 Y6.3744 I-0.0625 J0 -G1 X3.7077 Y6.3744 -G0 Z0.25 -G0 X3.9668 Y6.199 -G1 Z-0.05 F30 -G2 X4.1965 Y6.199 I0.1148 J-0.115 F10 -G2 X4.1526 Y6.2888 I0.1169 J0.1129 -G2 X4.1363 Y6.2993 I0.0792 J0.1419 -G1 X4.0817 Y6.3389 -G1 X4.0271 Y6.2993 -G2 X4.0108 Y6.2888 I-0.0955 J0.1315 -G2 X3.9668 Y6.199 I-0.1609 J0.023 -G2 X3.9648 Y6.1969 I-0.1169 J0.1129 -G2 X3.9668 Y6.199 I0.1169 J-0.1129 -G0 Z0.25 -G0 X4.1986 Y6.1969 -G1 Z-0.05 F30 -G2 X4.2369 Y6.1321 I-0.1169 J-0.1129 F10 -G1 X4.2529 Y6.0805 -G1 X4.2725 Y6.1408 -G1 X4.2179 Y6.1804 -G2 X4.1986 Y6.1969 I0.0955 J0.1315 -G0 Z0.25 -G0 X4.2473 Y6.2209 -G1 Z-0.05 F30 -G2 X4.2009 Y6.3119 I0.0661 J0.091 F10 -G2 X4.2014 Y6.3224 I0.1125 J0 -G2 X4.1656 Y6.3397 I0.0303 J0.1083 -G1 X4.0817 Y6.4007 -G1 X3.9977 Y6.3397 -G2 X3.9619 Y6.3224 I-0.0661 J0.091 -G2 X3.9624 Y6.3119 I-0.112 J-0.0105 -G2 X3.916 Y6.2209 I-0.1125 J0 -G1 X3.8321 Y6.1599 -G1 X3.8642 Y6.0612 -G2 X3.8697 Y6.0264 I-0.107 J-0.0348 -G2 X3.8695 Y6.0201 I-0.1125 J0 -G1 X3.9426 Y6.0201 -G1 X3.9747 Y6.1188 -G2 X4.1891 Y6.1173 I0.107 J-0.0347 -G1 X4.2192 Y6.0201 -G1 X4.2938 Y6.0201 -G2 X4.2937 Y6.0264 I0.1123 J0.0062 -G2 X4.2992 Y6.0612 I0.1125 J0 -G1 X4.3313 Y6.1599 -G1 X4.2473 Y6.2209 -G0 Z0.25 -G0 X4.1823 Y5.9701 -G1 Z-0.05 F30 -G1 X4.1414 Y6.1025 F10 -G3 X4.0222 Y6.1034 I-0.0597 J-0.0185 -G1 X3.979 Y5.9701 -G1 X3.8388 Y5.9701 -G3 X3.7763 Y5.9076 I0 J-0.0625 -G3 X3.802 Y5.857 I0.0625 J0 -G1 X3.9154 Y5.7747 -G1 X3.8721 Y5.6414 -G3 X3.8691 Y5.6221 I0.0594 J-0.0193 -G3 X3.9683 Y5.5715 I0.0625 J0 -G1 X4.0817 Y5.6539 -G1 X4.195 Y5.5715 -G3 X4.2943 Y5.6221 I0.0367 J0.0506 -G3 X4.2912 Y5.6414 I-0.0625 J0 -G1 X4.248 Y5.7747 -G1 X4.3613 Y5.857 -G3 X4.3871 Y5.9076 I-0.0367 J0.0506 -G3 X4.3246 Y5.9701 I-0.0625 J0 -G1 X4.1823 Y5.9701 -G0 Z0.25 -G0 X4.4481 Y5.802 -G1 Z-0.05 F30 -G2 X4.6648 Y5.8016 I0.1081 J-0.1213 F10 -G2 X4.6272 Y5.8844 I0.1232 J0.106 -G2 X4.6108 Y5.8949 I0.0792 J0.1419 -G1 X4.5563 Y5.9346 -G1 X4.5017 Y5.8949 -G2 X4.4854 Y5.8845 I-0.0955 J0.1315 -G2 X4.4481 Y5.802 I-0.1609 J0.0231 -G2 X4.4327 Y5.7863 I-0.1235 J0.1056 -G2 X4.4481 Y5.802 I0.1235 J-0.1056 -G0 Z0.25 -G0 X4.7471 Y5.7365 -G1 Z-0.05 F30 -G1 X4.6925 Y5.7761 F10 -G2 X4.6794 Y5.7867 I0.0955 J0.1315 -G2 X4.7115 Y5.7287 I-0.1232 J-0.106 -G1 X4.7276 Y5.6767 -G1 X4.7471 Y5.7365 -G0 Z0.25 -G0 X4.8059 Y5.7556 -G1 Z-0.05 F30 -G1 X4.7219 Y5.8166 F10 -G2 X4.6755 Y5.9076 I0.0661 J0.091 -G2 X4.676 Y5.918 I0.1125 J0 -G2 X4.6402 Y5.9353 I0.0303 J0.1083 -G1 X4.5563 Y5.9964 -G1 X4.4723 Y5.9353 -G2 X4.4366 Y5.9181 I-0.0661 J0.091 -G2 X4.4371 Y5.9076 I-0.112 J-0.0104 -G2 X4.3907 Y5.8166 I-0.1125 J0 -G1 X4.3067 Y5.7556 -G1 X4.3388 Y5.6568 -G2 X4.3443 Y5.6221 I-0.107 J-0.0347 -G2 X4.3441 Y5.6167 I-0.1125 J0 -G1 X4.4172 Y5.6167 -G1 X4.4492 Y5.7155 -G2 X4.6637 Y5.714 I0.107 J-0.0347 -G1 X4.6938 Y5.6167 -G1 X4.7684 Y5.6167 -G2 X4.7682 Y5.6221 I0.1124 J0.0054 -G2 X4.7738 Y5.6569 I0.1125 J0 -G1 X4.8059 Y5.7556 -G0 Z0.25 -G0 X4.6569 Y5.5667 -G1 Z-0.05 F30 -G1 X4.616 Y5.6992 F10 -G3 X4.4968 Y5.7 I-0.0597 J-0.0185 -G1 X4.4535 Y5.5667 -G1 X4.3134 Y5.5667 -G3 X4.2509 Y5.5042 I0 J-0.0625 -G3 X4.2767 Y5.4536 I0.0625 J0 -G1 X4.3901 Y5.3712 -G1 X4.3467 Y5.238 -G3 X4.3437 Y5.2186 I0.0594 J-0.0193 -G3 X4.4429 Y5.1681 I0.0625 J0 -G1 X4.5563 Y5.2505 -G1 X4.6696 Y5.1681 -G3 X4.7689 Y5.2186 I0.0367 J0.0506 -G3 X4.7658 Y5.2379 I-0.0625 J0 -G1 X4.7225 Y5.3712 -G1 X4.8359 Y5.4536 -G3 X4.8617 Y5.5042 I-0.0367 J0.0506 -G3 X4.7992 Y5.5667 I-0.0625 J0 -G1 X4.6569 Y5.5667 -G0 Z0.25 -G0 X4.8763 Y5.3257 -G1 Z-0.05 F30 -G2 X5.1861 Y5.3235 I0.1546 J-0.0502 F10 -G1 X5.202 Y5.2722 -G1 X5.2217 Y5.333 -G1 X5.1671 Y5.3727 -G2 X5.1019 Y5.4802 I0.0955 J0.1315 -G2 X5.0856 Y5.4906 I0.0792 J0.1419 -G1 X5.0309 Y5.5303 -G1 X4.9763 Y5.4906 -G2 X4.9599 Y5.4802 I-0.0955 J0.1315 -G2 X4.8947 Y5.3727 I-0.1607 J0.024 -G1 X4.8401 Y5.333 -G1 X4.8594 Y5.2736 -G1 X4.8763 Y5.3257 -G1 X4.9238 Y5.3103 F10 -G2 X5.1383 Y5.3088 I0.107 J-0.0347 F10 -G1 X5.1684 Y5.2116 -G1 X5.2431 Y5.2116 -G2 X5.2429 Y5.2186 I0.1123 J0.0071 -G2 X5.2484 Y5.2534 I0.1125 J0 -G1 X5.2805 Y5.3521 -G1 X5.1965 Y5.4132 -G2 X5.1501 Y5.5042 I0.0661 J0.091 -G2 X5.1505 Y5.5138 I0.1125 J0 -G2 X5.115 Y5.531 I0.0305 J0.1083 -G1 X5.0309 Y5.5921 -G1 X4.9469 Y5.5311 -G2 X4.9113 Y5.5138 I-0.0661 J0.091 -G2 X4.9117 Y5.5042 I-0.1121 J-0.0096 -G2 X4.8653 Y5.4132 I-0.1125 J0 -G1 X4.7813 Y5.3521 -G1 X4.8134 Y5.2534 -G2 X4.8189 Y5.2186 I-0.107 J-0.0347 -G2 X4.8186 Y5.2116 I-0.1125 J0 -G1 X4.8918 Y5.2116 -G1 X4.9238 Y5.3103 -G0 Z0.25 -G0 X5.1315 Y5.1616 -G1 Z-0.05 F30 -G1 X5.0905 Y5.294 F10 -G3 X4.9714 Y5.2948 I-0.0597 J-0.0185 -G1 X4.9281 Y5.1616 -G1 X4.788 Y5.1616 -G3 X4.7255 Y5.0991 I0 J-0.0625 -G3 X4.7513 Y5.0485 I0.0625 J0 -G1 X4.8646 Y4.9661 -G1 X4.8213 Y4.8329 -G3 X4.8182 Y4.8135 I0.0594 J-0.0193 -G3 X4.9175 Y4.763 I0.0625 J0 -G1 X5.0309 Y4.8454 -G1 X5.1443 Y4.763 -G3 X5.2435 Y4.8135 I0.0367 J0.0506 -G3 X5.2405 Y4.8329 I-0.0625 J0 -G1 X5.1971 Y4.9661 -G1 X5.3105 Y5.0485 -G3 X5.3363 Y5.0991 I-0.0367 J0.0506 -G3 X5.2738 Y5.1616 I-0.0625 J0 -G1 X5.1315 Y5.1616 -G0 Z0.25 -G0 X5.351 Y4.9214 -G1 Z-0.05 F30 -G2 X5.6608 Y4.9191 I0.1545 J-0.0503 F10 -G1 X5.6799 Y4.8572 -G1 X5.7239 Y4.8572 -G1 X5.7239 Y5.0712 -G2 X5.5601 Y5.0872 I-0.0682 J0.1475 -G1 X5.5055 Y5.1268 -G1 X5.4509 Y5.0872 -G2 X5.4347 Y5.0768 I-0.0955 J0.1315 -G2 X5.3693 Y4.9676 I-0.161 J0.0223 -G1 X5.3147 Y4.928 -G1 X5.3339 Y4.8689 -G1 X5.351 Y4.9214 -G1 X5.3985 Y4.9059 F10 -G2 X5.613 Y4.9043 I0.107 J-0.0348 F10 -G1 X5.643 Y4.8072 -G1 X5.7483 Y4.8072 -G2 X5.7739 Y4.8043 I0 J-0.1125 -G1 X5.7739 Y5.3836 -G1 X5.7305 Y5.3521 -G1 X5.7626 Y5.2534 -G2 X5.7681 Y5.2186 I-0.107 J-0.0348 -G2 X5.5895 Y5.1276 I-0.1125 J0 -G1 X5.5055 Y5.1886 -G1 X5.4216 Y5.1276 -G2 X5.3857 Y5.1103 I-0.0661 J0.091 -G2 X5.3863 Y5.0991 I-0.1119 J-0.0112 -G2 X5.3399 Y5.008 I-0.1125 J0 -G1 X5.2559 Y4.947 -G1 X5.288 Y4.8483 -G2 X5.2935 Y4.8135 I-0.107 J-0.0348 -G2 X5.2934 Y4.8072 I-0.1125 J0 -G1 X5.3664 Y4.8072 -G1 X5.3985 Y4.9059 -G0 Z0.25 -G0 X5.6061 Y4.7572 -G1 Z-0.05 F30 -G1 X5.5652 Y4.8896 F10 -G3 X5.4461 Y4.8905 I-0.0597 J-0.0184 -G1 X5.4027 Y4.7572 -G1 X5.2626 Y4.7572 -G3 X5.2001 Y4.6947 I0 J-0.0625 -G3 X5.2259 Y4.6441 I0.0625 J0 -G1 X5.3393 Y4.5617 -G1 X5.296 Y4.4285 -G3 X5.2929 Y4.4092 I0.0594 J-0.0193 -G3 X5.3922 Y4.3586 I0.0625 J0 -G1 X5.5055 Y4.441 -G1 X5.6189 Y4.3586 -G3 X5.7181 Y4.4092 I0.0367 J0.0506 -G3 X5.7151 Y4.4285 I-0.0625 J0 -G1 X5.6717 Y4.5618 -G1 X5.7851 Y4.6441 -G3 X5.8108 Y4.6947 I-0.0367 J0.0506 -G3 X5.7483 Y4.7572 I-0.0625 J0 -G1 X5.6061 Y4.7572 -G0 Z0.25 -G0 X5.3907 Y4.1776 -G1 Z-0.05 F30 -G2 X5.6608 Y4.1105 I0.1148 J-0.115 F10 -G1 X5.6799 Y4.0486 -G1 X5.7239 Y4.0486 -G1 X5.7239 Y4.2617 -G2 X5.5601 Y4.2777 I-0.0682 J0.1475 -G1 X5.5055 Y4.3174 -G1 X5.4509 Y4.2777 -G2 X5.4346 Y4.2673 I-0.0955 J0.1315 -G2 X5.3907 Y4.1776 I-0.1608 J0.0232 -G2 X5.3886 Y4.1755 I-0.1169 J0.1129 -G2 X5.3907 Y4.1776 I0.1169 J-0.1129 -G1 X5.3399 Y4.1994 F10 -G1 X5.2559 Y4.1384 F10 -G1 X5.288 Y4.0397 -G2 X5.2935 Y4.0049 I-0.107 J-0.0348 -G2 X5.2934 Y3.9986 I-0.1125 J0 -G1 X5.3664 Y3.9986 -G1 X5.3985 Y4.0974 -G2 X5.613 Y4.0958 I0.107 J-0.0348 -G1 X5.643 Y3.9986 -G1 X5.7483 Y3.9986 -G2 X5.7739 Y3.9957 I0 J-0.1125 -G1 X5.7739 Y4.5742 -G1 X5.7305 Y4.5427 -G1 X5.7626 Y4.444 -G2 X5.7681 Y4.4092 I-0.107 J-0.0348 -G2 X5.5895 Y4.3182 I-0.1125 J0 -G1 X5.5055 Y4.3792 -G1 X5.4216 Y4.3182 -G2 X5.3858 Y4.3008 I-0.0661 J0.091 -G2 X5.3863 Y4.2904 I-0.112 J-0.0104 -G2 X5.3399 Y4.1994 I-0.1125 J0 -G0 Z0.25 -G0 X5.459 Y3.5986 -G1 Z-0.05 F30 -G1 X5.552 Y3.5986 F10 -G1 X5.5055 Y3.6324 -G1 X5.459 Y3.5986 -G0 Z0.25 -G0 X5.7151 Y3.62 -G1 Z-0.05 F30 -G2 X5.7181 Y3.6006 I-0.0594 J-0.0193 F10 -G2 X5.7181 Y3.5986 I-0.0625 J0 -G1 X5.8239 Y3.5986 -G1 X5.8239 Y7.3174 -G1 X5.5649 Y7.3174 -G2 X5.5652 Y7.3163 I-0.0594 J-0.0195 -G1 X5.6061 Y7.1839 -G1 X5.7483 Y7.1839 -G2 X5.8108 Y7.1214 I0 J-0.0625 -G2 X5.7851 Y7.0708 I-0.0625 J0 -G1 X5.6717 Y6.9884 -G1 X5.7151 Y6.8552 -G2 X5.7181 Y6.8358 I-0.0594 J-0.0193 -G2 X5.6189 Y6.7853 I-0.0625 J0 -G1 X5.5055 Y6.8676 -G1 X5.3922 Y6.7853 -G2 X5.2929 Y6.8358 I-0.0367 J0.0506 -G2 X5.296 Y6.8551 I0.0625 J0 -G1 X5.3393 Y6.9884 -G1 X5.2259 Y7.0708 -G2 X5.2001 Y7.1214 I0.0367 J0.0506 -G2 X5.2626 Y7.1839 I0.0625 J0 -G1 X5.4027 Y7.1839 -G1 X5.4461 Y7.3172 -G1 X5.4461 Y7.3174 -G1 X4.6156 Y7.3174 -G2 X4.616 Y7.3164 I-0.0594 J-0.0195 -G1 X4.6569 Y7.1839 -G1 X4.7992 Y7.1839 -G2 X4.8617 Y7.1214 I0 J-0.0625 -G2 X4.8359 Y7.0708 I-0.0625 J0 -G1 X4.7225 Y6.9884 -G1 X4.7658 Y6.8551 -G2 X4.7689 Y6.8358 I-0.0594 J-0.0193 -G2 X4.6696 Y6.7853 I-0.0625 J0 -G1 X4.5563 Y6.8676 -G1 X4.4429 Y6.7853 -G2 X4.3437 Y6.8358 I-0.0367 J0.0506 -G2 X4.3467 Y6.8552 I0.0625 J0 -G1 X4.3901 Y6.9884 -G1 X4.2767 Y7.0708 -G2 X4.2509 Y7.1214 I0.0367 J0.0506 -G2 X4.3134 Y7.1839 I0.0625 J0 -G1 X4.4535 Y7.1839 -G1 X4.4968 Y7.3172 -G1 X4.4969 Y7.3174 -G1 X3.6665 Y7.3174 -G2 X3.6668 Y7.3163 I-0.0594 J-0.0195 -G1 X3.7077 Y7.1839 -G1 X3.8499 Y7.1839 -G2 X3.9124 Y7.1214 I0 J-0.0625 -G2 X3.8866 Y7.0708 I-0.0625 J0 -G1 X3.7733 Y6.9884 -G1 X3.8166 Y6.8552 -G2 X3.8197 Y6.8358 I-0.0594 J-0.0193 -G2 X3.7205 Y6.7853 I-0.0625 J0 -G1 X3.6071 Y6.8676 -G1 X3.4937 Y6.7853 -G2 X3.3945 Y6.8358 I-0.0367 J0.0506 -G2 X3.3975 Y6.8551 I0.0625 J0 -G1 X3.4408 Y6.9884 -G1 X3.3274 Y7.0708 -G2 X3.3017 Y7.1214 I0.0367 J0.0506 -G2 X3.3642 Y7.1839 I0.0625 J0 -G1 X3.5043 Y7.1839 -G1 X3.5477 Y7.3172 -G1 X3.5477 Y7.3174 -G1 X2.7172 Y7.3174 -G2 X2.7175 Y7.3164 I-0.0594 J-0.0195 -G1 X2.7585 Y7.1839 -G1 X2.9007 Y7.1839 -G2 X2.9632 Y7.1214 I0 J-0.0625 -G2 X2.9375 Y7.0708 I-0.0625 J0 -G1 X2.8241 Y6.9884 -G1 X2.8674 Y6.8551 -G2 X2.8704 Y6.8358 I-0.0594 J-0.0193 -G2 X2.7712 Y6.7853 I-0.0625 J0 -G1 X2.6578 Y6.8676 -G1 X2.5445 Y6.7853 -G2 X2.4452 Y6.8358 I-0.0367 J0.0506 -G2 X2.4483 Y6.8552 I0.0625 J0 -G1 X2.4916 Y6.9884 -G1 X2.3783 Y7.0708 -G2 X2.3525 Y7.1214 I0.0367 J0.0506 -G2 X2.415 Y7.1839 I0.0625 J0 -G1 X2.5551 Y7.1839 -G1 X2.5984 Y7.3172 -G1 X2.5984 Y7.3174 -G1 X1.768 Y7.3174 -G2 X1.7684 Y7.3163 I-0.0594 J-0.0195 -G1 X1.8093 Y7.1839 -G1 X1.9515 Y7.1839 -G2 X2.014 Y7.1214 I0 J-0.0625 -G2 X1.9882 Y7.0708 I-0.0625 J0 -G1 X1.8748 Y6.9884 -G1 X1.9182 Y6.8552 -G2 X1.9213 Y6.8358 I-0.0594 J-0.0193 -G2 X1.822 Y6.7853 I-0.0625 J0 -G1 X1.7087 Y6.8676 -G1 X1.5953 Y6.7853 -G2 X1.496 Y6.8358 I-0.0367 J0.0506 -G2 X1.4991 Y6.8551 I0.0625 J0 -G1 X1.5424 Y6.9884 -G1 X1.429 Y7.0708 -G2 X1.4032 Y7.1214 I0.0367 J0.0506 -G2 X1.4657 Y7.1839 I0.0625 J0 -G1 X1.6059 Y7.1839 -G1 X1.6492 Y7.3172 -G1 X1.6493 Y7.3174 -G1 X0.8188 Y7.3174 -G2 X0.8191 Y7.3164 I-0.0594 J-0.0195 -G1 X0.8601 Y7.1839 -G1 X1.0023 Y7.1839 -G2 X1.0648 Y7.1214 I0 J-0.0625 -G2 X1.039 Y7.0708 I-0.0625 J0 -G1 X0.9257 Y6.9884 -G1 X0.9689 Y6.8551 -G2 X0.972 Y6.8358 I-0.0594 J-0.0193 -G2 X0.8727 Y6.7853 I-0.0625 J0 -G1 X0.7594 Y6.8676 -G1 X0.646 Y6.7853 -G2 X0.5468 Y6.8358 I-0.0367 J0.0506 -G2 X0.5498 Y6.8552 I0.0625 J0 -G1 X0.5932 Y6.9884 -G1 X0.4798 Y7.0708 -G2 X0.4541 Y7.1214 I0.0367 J0.0506 -G2 X0.5166 Y7.1839 I0.0625 J0 -G1 X0.6567 Y7.1839 -G1 X0.6999 Y7.3172 -G1 X0.7 Y7.3174 -G1 X0.441 Y7.3174 -G1 X0.441 Y3.5986 -G1 X0.5468 Y3.5986 -G2 X0.5468 Y3.6006 I0.0625 J0.002 -G2 X0.5498 Y3.62 I0.0625 J0 -G1 X0.5932 Y3.7532 -G1 X0.4798 Y3.8356 -G2 X0.4541 Y3.8861 I0.0367 J0.0506 -G2 X0.5166 Y3.9486 I0.0625 J0 -G1 X0.6567 Y3.9486 -G1 X0.6999 Y4.0819 -G2 X0.8191 Y4.0811 I0.0594 J-0.0193 -G1 X0.8601 Y3.9486 -G1 X1.0023 Y3.9486 -G2 X1.0648 Y3.8861 I0 J-0.0625 -G2 X1.039 Y3.8356 I-0.0625 J0 -G1 X0.9257 Y3.7532 -G1 X0.9689 Y3.6199 -G2 X0.972 Y3.6006 I-0.0594 J-0.0193 -G2 X0.972 Y3.5986 I-0.0625 J0 -G1 X1.4961 Y3.5986 -G2 X1.496 Y3.6006 I0.0625 J0.002 -G2 X1.4991 Y3.6199 I0.0625 J0 -G1 X1.5424 Y3.7532 -G1 X1.429 Y3.8356 -G2 X1.4032 Y3.8861 I0.0367 J0.0506 -G2 X1.4657 Y3.9486 I0.0625 J0 -G1 X1.6059 Y3.9486 -G1 X1.6492 Y4.0819 -G2 X1.7684 Y4.081 I0.0594 J-0.0193 -G1 X1.8092 Y3.9486 -G1 X1.9515 Y3.9486 -G2 X2.014 Y3.8861 I0 J-0.0625 -G2 X1.9882 Y3.8356 I-0.0625 J0 -G1 X1.8748 Y3.7532 -G1 X1.9182 Y3.62 -G2 X1.9213 Y3.6006 I-0.0594 J-0.0193 -G2 X1.9212 Y3.5986 I-0.0625 J0 -G1 X2.4452 Y3.5986 -G2 X2.4452 Y3.6006 I0.0625 J0.002 -G2 X2.4483 Y3.62 I0.0625 J0 -G1 X2.4916 Y3.7532 -G1 X2.3783 Y3.8356 -G2 X2.3525 Y3.8861 I0.0367 J0.0506 -G2 X2.415 Y3.9486 I0.0625 J0 -G1 X2.5551 Y3.9486 -G1 X2.5984 Y4.0819 -G2 X2.7175 Y4.0811 I0.0594 J-0.0193 -G1 X2.7585 Y3.9486 -G1 X2.9007 Y3.9486 -G2 X2.9632 Y3.8861 I0 J-0.0625 -G2 X2.9375 Y3.8356 I-0.0625 J0 -G1 X2.8241 Y3.7532 -G1 X2.8674 Y3.6199 -G2 X2.8704 Y3.6006 I-0.0594 J-0.0193 -G2 X2.8704 Y3.5986 I-0.0625 J0 -G1 X3.3945 Y3.5986 -G2 X3.3945 Y3.6006 I0.0625 J0.002 -G2 X3.3975 Y3.6199 I0.0625 J0 -G1 X3.4408 Y3.7532 -G1 X3.3274 Y3.8356 -G2 X3.3017 Y3.8861 I0.0367 J0.0506 -G2 X3.3642 Y3.9486 I0.0625 J0 -G1 X3.5043 Y3.9486 -G1 X3.5477 Y4.0819 -G2 X3.6668 Y4.081 I0.0594 J-0.0193 -G1 X3.7077 Y3.9486 -G1 X3.8499 Y3.9486 -G2 X3.9124 Y3.8861 I0 J-0.0625 -G2 X3.8866 Y3.8356 I-0.0625 J0 -G1 X3.7733 Y3.7532 -G1 X3.8166 Y3.62 -G2 X3.8197 Y3.6006 I-0.0594 J-0.0193 -G2 X3.8197 Y3.5986 I-0.0625 J0 -G1 X4.3437 Y3.5986 -G2 X4.3437 Y3.6006 I0.0625 J0.002 -G2 X4.3467 Y3.62 I0.0625 J0 -G1 X4.3901 Y3.7532 -G1 X4.2767 Y3.8356 -G2 X4.2509 Y3.8861 I0.0367 J0.0506 -G2 X4.3134 Y3.9486 I0.0625 J0 -G1 X4.4535 Y3.9486 -G1 X4.4968 Y4.0819 -G2 X4.616 Y4.0811 I0.0594 J-0.0193 -G1 X4.6569 Y3.9486 -G1 X4.7992 Y3.9486 -G2 X4.8617 Y3.8861 I0 J-0.0625 -G2 X4.8359 Y3.8356 I-0.0625 J0 -G1 X4.7225 Y3.7532 -G1 X4.7658 Y3.6199 -G2 X4.7689 Y3.6006 I-0.0594 J-0.0193 -G2 X4.7688 Y3.5986 I-0.0625 J0 -G1 X5.293 Y3.5986 -G2 X5.2929 Y3.6006 I0.0625 J0.002 -G2 X5.296 Y3.6199 I0.0625 J0 -G1 X5.3393 Y3.7532 -G1 X5.2259 Y3.8356 -G2 X5.2001 Y3.8861 I0.0367 J0.0506 -G2 X5.2626 Y3.9486 I0.0625 J0 -G1 X5.4027 Y3.9486 -G1 X5.4461 Y4.0819 -G2 X5.5652 Y4.081 I0.0594 J-0.0193 -G1 X5.6061 Y3.9486 -G1 X5.7483 Y3.9486 -G2 X5.8108 Y3.8861 I0 J-0.0625 -G2 X5.7851 Y3.8356 I-0.0625 J0 -G1 X5.6717 Y3.7532 -G1 X5.7151 Y3.62 -G0 Z0.25 -G0 X5.7739 Y3.6486 -G1 Z-0.05 F30 -G1 X5.7739 Y3.7656 F10 -G1 X5.7305 Y3.7341 -G1 X5.7583 Y3.6486 -G1 X5.7739 Y3.6486 -G0 Z0.25 -G0 X4.9612 Y3.7486 -G1 Z-0.05 F30 -G1 X5.1006 Y3.7486 F10 -G2 X5.057 Y3.8323 I0.162 J0.1375 -G2 X5.0562 Y3.8329 I0.124 J0.1726 -G1 X5.0309 Y3.8513 -G1 X5.0056 Y3.833 -G2 X5.0047 Y3.8323 I-0.1249 J0.1719 -G2 X4.9612 Y3.7486 I-0.2056 J0.0538 -G1 X4.8947 Y3.7547 F10 -G1 X4.8401 Y3.715 F10 -G1 X4.8454 Y3.6986 -G1 X5.2164 Y3.6986 -G1 X5.2217 Y3.715 -G1 X5.1671 Y3.7547 -G2 X5.1018 Y3.8631 I0.0955 J0.1315 -G2 X5.0856 Y3.8734 I0.0793 J0.1418 -G1 X5.0309 Y3.9131 -G1 X4.9763 Y3.8734 -G2 X4.96 Y3.8631 I-0.0955 J0.1315 -G2 X4.8947 Y3.7547 I-0.1609 J0.0231 -G1 X4.8653 Y3.7951 F10 -G1 X4.7813 Y3.7341 F10 -G1 X4.8091 Y3.6486 -G1 X5.2527 Y3.6486 -G1 X5.2805 Y3.7341 -G1 X5.1965 Y3.7951 -G2 X5.1501 Y3.8861 I0.0661 J0.091 -G2 X5.1506 Y3.8966 I0.1125 J0 -G2 X5.115 Y3.9139 I0.0305 J0.1083 -G1 X5.0309 Y3.9749 -G1 X4.9469 Y3.9139 -G2 X4.9112 Y3.8966 I-0.0661 J0.091 -G2 X4.9117 Y3.8861 I-0.112 J-0.0104 -G2 X4.8653 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X4.5098 Y3.5986 -G1 Z-0.05 F30 -G1 X4.6028 Y3.5986 F10 -G1 X4.5563 Y3.6324 -G1 X4.5098 Y3.5986 - -(follow path 2) -G0 Z0.25 -G0 X4.0119 Y3.7486 -G1 Z-0.05 F30 -G1 X4.1514 Y3.7486 F10 -G2 X4.1079 Y3.8322 I0.162 J0.1375 -G2 X4.1069 Y3.833 I0.1239 J0.1727 -G1 X4.0817 Y3.8513 -G1 X4.0565 Y3.833 -G2 X4.0555 Y3.8322 I-0.1249 J0.1719 -G2 X4.0119 Y3.7486 I-0.2055 J0.0539 -G1 X3.9454 Y3.7547 F10 -G1 X3.8909 Y3.715 F10 -G1 X3.8962 Y3.6986 -G1 X4.2672 Y3.6986 -G1 X4.2725 Y3.715 -G1 X4.2179 Y3.7547 -G2 X4.1526 Y3.863 I0.0955 J0.1315 -G2 X4.1363 Y3.8734 I0.0792 J0.1419 -G1 X4.0817 Y3.9131 -G1 X4.0271 Y3.8734 -G2 X4.0107 Y3.863 I-0.0955 J0.1315 -G2 X3.9454 Y3.7547 I-0.1608 J0.0232 -G1 X3.916 Y3.7951 F10 -G1 X3.8321 Y3.7341 F10 -G1 X3.8599 Y3.6486 -G1 X4.3035 Y3.6486 -G1 X4.3313 Y3.7341 -G1 X4.2473 Y3.7951 -G2 X4.2009 Y3.8861 I0.0661 J0.091 -G2 X4.2014 Y3.8966 I0.1125 J0 -G2 X4.1656 Y3.9139 I0.0303 J0.1083 -G1 X4.0817 Y3.9749 -G1 X3.9977 Y3.9139 -G2 X3.9619 Y3.8966 I-0.0661 J0.091 -G2 X3.9624 Y3.8861 I-0.112 J-0.0104 -G2 X3.916 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X3.7726 Y4.1994 -G1 Z-0.05 F30 -G2 X3.7263 Y4.2904 I0.0661 J0.091 F10 -G2 X3.7267 Y4.3009 I0.1125 J0 -G2 X3.6911 Y4.3182 I0.0305 J0.1083 -G1 X3.6071 Y4.3792 -G1 X3.5231 Y4.3182 -G2 X3.4873 Y4.3008 I-0.0661 J0.091 -G2 X3.4878 Y4.2904 I-0.112 J-0.0104 -G2 X3.4414 Y4.1994 I-0.1125 J0 -G1 X3.3575 Y4.1384 -G1 X3.3896 Y4.0397 -G2 X3.3951 Y4.0049 I-0.107 J-0.0348 -G2 X3.3949 Y3.9986 I-0.1125 J0 -G1 X3.468 Y3.9986 -G1 X3.5001 Y4.0974 -G2 X3.7146 Y4.0958 I0.107 J-0.0348 -G1 X3.7446 Y3.9986 -G1 X3.8192 Y3.9986 -G2 X3.8191 Y4.0049 I0.1123 J0.0062 -G2 X3.8246 Y4.0396 I0.1125 J0 -G1 X3.8566 Y4.1384 -G1 X3.7726 Y4.1994 -G0 Z0.25 -G0 X3.7256 Y4.1738 -G1 Z-0.05 F30 -G2 X3.7624 Y4.1105 I-0.1185 J-0.1112 F10 -G1 X3.7783 Y4.059 -G1 X3.7979 Y4.1193 -G1 X3.7432 Y4.159 -G2 X3.7256 Y4.1738 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.4922 Y4.1776 -G1 Z-0.05 F30 -G2 X3.7203 Y4.1792 I0.1148 J-0.115 F10 -G2 X3.6779 Y4.2673 I0.1185 J0.1112 -G2 X3.6617 Y4.2777 I0.0793 J0.1418 -G1 X3.6071 Y4.3174 -G1 X3.5525 Y4.2777 -G2 X3.5362 Y4.2673 I-0.0955 J0.1315 -G2 X3.4922 Y4.1776 I-0.1608 J0.0232 -G2 X3.4902 Y4.1755 I-0.1169 J0.1129 -G2 X3.4922 Y4.1776 I0.1169 J-0.1129 -G0 Z0.25 -G0 X3.2331 Y4.3529 -G1 Z-0.05 F30 -G1 X3.1921 Y4.4853 F10 -G3 X3.073 Y4.4862 I-0.0597 J-0.0185 -G1 X3.0297 Y4.3529 -G1 X2.8896 Y4.3529 -G3 X2.8271 Y4.2904 I0 J-0.0625 -G3 X2.8529 Y4.2399 I0.0625 J0 -G1 X2.9662 Y4.1575 -G1 X2.9229 Y4.0242 -G3 X2.9198 Y4.0049 I0.0594 J-0.0193 -G3 X3.019 Y3.9543 I0.0625 J0 -G1 X3.1324 Y4.0367 -G1 X3.2459 Y3.9543 -G3 X3.3451 Y4.0049 I0.0367 J0.0506 -G3 X3.342 Y4.0242 I-0.0625 J0 -G1 X3.2987 Y4.1575 -G1 X3.4121 Y4.2399 -G3 X3.4378 Y4.2904 I-0.0367 J0.0506 -G3 X3.3753 Y4.3529 I-0.0625 J0 -G1 X3.2331 Y4.3529 -G0 Z0.25 -G0 X3.2493 Y4.5797 -G1 Z-0.05 F30 -G2 X3.2876 Y4.5149 I-0.1169 J-0.1129 F10 -G1 X3.3037 Y4.4631 -G1 X3.3233 Y4.5235 -G1 X3.2687 Y4.5632 -G2 X3.2493 Y4.5797 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.298 Y4.6037 -G1 Z-0.05 F30 -G2 X3.2517 Y4.6947 I0.0661 J0.091 F10 -G2 X3.2522 Y4.7052 I0.1125 J0 -G2 X3.2165 Y4.7225 I0.0304 J0.1083 -G1 X3.1324 Y4.7836 -G1 X3.0484 Y4.7225 -G2 X3.0127 Y4.7052 I-0.0661 J0.091 -G2 X3.0132 Y4.6947 I-0.112 J-0.0106 -G2 X2.9669 Y4.6037 I-0.1125 J0 -G1 X2.8829 Y4.5426 -G1 X2.9149 Y4.4439 -G2 X2.9204 Y4.4092 I-0.107 J-0.0347 -G2 X2.9202 Y4.4029 I-0.1125 J0 -G1 X2.9934 Y4.4029 -G1 X3.0254 Y4.5016 -G2 X3.2399 Y4.5001 I0.107 J-0.0347 -G1 X3.2699 Y4.4029 -G1 X3.3447 Y4.4029 -G2 X3.3445 Y4.4092 I0.1123 J0.0062 -G2 X3.35 Y4.4439 I0.1125 J0 -G1 X3.382 Y4.5426 -G1 X3.298 Y4.6037 -G0 Z0.25 -G0 X3.0192 Y4.5835 -G1 Z-0.05 F30 -G2 X3.2473 Y4.5818 I0.1132 J-0.1166 F10 -G2 X3.2033 Y4.6717 I0.1169 J0.1129 -G2 X3.1871 Y4.682 I0.0793 J0.1418 -G1 X3.1324 Y4.7218 -G1 X3.0778 Y4.6821 -G2 X3.0616 Y4.6717 I-0.0955 J0.1315 -G2 X3.0192 Y4.5835 I-0.1609 J0.023 -G2 X3.0139 Y4.5781 I-0.1185 J0.1112 -G2 X3.0192 Y4.5835 I0.1185 J-0.1112 -G0 Z0.25 -G0 X2.7585 Y4.7572 -G1 Z-0.05 F30 -G1 X2.7175 Y4.8896 F10 -G3 X2.5984 Y4.8904 I-0.0597 J-0.0185 -G1 X2.5551 Y4.7572 -G1 X2.415 Y4.7572 -G3 X2.3525 Y4.6947 I0 J-0.0625 -G3 X2.3783 Y4.6441 I0.0625 J0 -G1 X2.4916 Y4.5618 -G1 X2.4483 Y4.4285 -G3 X2.4452 Y4.4092 I0.0594 J-0.0193 -G3 X2.5445 Y4.3586 I0.0625 J0 -G1 X2.6578 Y4.441 -G1 X2.7712 Y4.3586 -G3 X2.8704 Y4.4092 I0.0367 J0.0506 -G3 X2.8674 Y4.4285 I-0.0625 J0 -G1 X2.8241 Y4.5617 -G1 X2.9375 Y4.6441 -G3 X2.9632 Y4.6947 I-0.0367 J0.0506 -G3 X2.9007 Y4.7572 I-0.0625 J0 -G1 X2.7585 Y4.7572 -G0 Z0.25 -G0 X2.5431 Y4.9862 -G1 Z-0.05 F30 -G2 X2.8131 Y4.9192 I0.1147 J-0.1151 F10 -G1 X2.829 Y4.8676 -G1 X2.8486 Y4.928 -G1 X2.7941 Y4.9676 -G2 X2.7286 Y5.0768 I0.0955 J0.1315 -G2 X2.7124 Y5.0872 I0.0793 J0.1418 -G1 X2.6578 Y5.1268 -G1 X2.6032 Y5.0872 -G2 X2.5871 Y5.0769 I-0.0955 J0.1315 -G2 X2.5431 Y4.9862 I-0.161 J0.0222 -G2 X2.5409 Y4.984 I-0.1169 J0.1129 -G2 X2.5431 Y4.9862 I0.1169 J-0.1129 -G1 X2.4923 Y5.008 F10 -G1 X2.4083 Y4.947 F10 -G1 X2.4403 Y4.8483 -G2 X2.4458 Y4.8135 I-0.107 J-0.0347 -G2 X2.4457 Y4.8072 I-0.1125 J0 -G1 X2.5188 Y4.8072 -G1 X2.5508 Y4.9059 -G2 X2.7653 Y4.9044 I0.107 J-0.0347 -G1 X2.7954 Y4.8072 -G1 X2.87 Y4.8072 -G2 X2.8698 Y4.8135 I0.1123 J0.0064 -G2 X2.8753 Y4.8483 I0.1125 J0 -G1 X2.9074 Y4.947 -G1 X2.8235 Y5.008 -G2 X2.7771 Y5.0991 I0.0661 J0.091 -G2 X2.7777 Y5.1103 I0.1125 J0 -G2 X2.7418 Y5.1276 I0.0303 J0.1084 -G1 X2.6578 Y5.1886 -G1 X2.5738 Y5.1276 -G2 X2.5381 Y5.1103 I-0.0661 J0.091 -G2 X2.5387 Y5.0991 I-0.1119 J-0.0113 -G2 X2.4923 Y5.008 I-0.1125 J0 -G0 Z0.25 -G0 X2.2839 Y5.1616 -G1 Z-0.05 F30 -G1 X2.2429 Y5.294 F10 -G3 X2.1238 Y5.2948 I-0.0597 J-0.0185 -G1 X2.0805 Y5.1616 -G1 X1.9403 Y5.1616 -G3 X1.8778 Y5.0991 I0 J-0.0625 -G3 X1.9036 Y5.0485 I0.0625 J0 -G1 X2.017 Y4.9661 -G1 X1.9737 Y4.8328 -G3 X1.9706 Y4.8135 I0.0594 J-0.0193 -G3 X2.0699 Y4.763 I0.0625 J0 -G1 X2.1832 Y4.8453 -G1 X2.2966 Y4.763 -G3 X2.3958 Y4.8135 I0.0367 J0.0506 -G3 X2.3928 Y4.8328 I-0.0625 J0 -G1 X2.3495 Y4.9661 -G1 X2.4629 Y5.0485 -G3 X2.4887 Y5.0991 I-0.0367 J0.0506 -G3 X2.4262 Y5.1616 I-0.0625 J0 -G1 X2.2839 Y5.1616 -G0 Z0.25 -G0 X2.0287 Y5.3257 -G1 Z-0.05 F30 -G2 X2.3385 Y5.3235 I0.1546 J-0.0502 F10 -G1 X2.3543 Y5.2724 -G1 X2.3741 Y5.3331 -G1 X2.3195 Y5.3727 -G2 X2.2543 Y5.4801 I0.0955 J0.1315 -G2 X2.2378 Y5.4906 I0.079 J0.142 -G1 X2.1832 Y5.5303 -G1 X2.1286 Y5.4906 -G2 X2.1122 Y5.4801 I-0.0955 J0.1315 -G2 X2.047 Y5.3727 I-0.1607 J0.0241 -G1 X1.9924 Y5.3331 -G1 X2.0118 Y5.2736 -G1 X2.0287 Y5.3257 -G1 X2.0762 Y5.3103 F10 -G2 X2.2907 Y5.3088 I0.107 J-0.0347 F10 -G1 X2.3208 Y5.2116 -G1 X2.3954 Y5.2116 -G2 X2.3952 Y5.2186 I0.1123 J0.0071 -G2 X2.4007 Y5.2534 I0.1125 J0 -G1 X2.4328 Y5.3521 -G1 X2.3489 Y5.4132 -G2 X2.3025 Y5.5042 I0.0661 J0.091 -G2 X2.3029 Y5.5138 I0.1125 J0 -G2 X2.2672 Y5.5311 I0.0304 J0.1083 -G1 X2.1832 Y5.5921 -G1 X2.0993 Y5.5311 -G2 X2.0636 Y5.5138 I-0.0661 J0.091 -G2 X2.064 Y5.5042 I-0.1121 J-0.0096 -G2 X2.0176 Y5.4132 I-0.1125 J0 -G1 X1.9336 Y5.3521 -G1 X1.9657 Y5.2534 -G2 X1.9713 Y5.2186 I-0.107 J-0.0348 -G2 X1.971 Y5.2116 I-0.1125 J0 -G1 X2.0442 Y5.2116 -G1 X2.0762 Y5.3103 -G0 Z0.25 -G0 X1.8093 Y5.5667 -G1 Z-0.05 F30 -G1 X1.7684 Y5.6992 F10 -G3 X1.6492 Y5.7001 I-0.0597 J-0.0184 -G1 X1.6059 Y5.5667 -G1 X1.4657 Y5.5667 -G3 X1.4032 Y5.5042 I0 J-0.0625 -G3 X1.429 Y5.4536 I0.0625 J0 -G1 X1.5424 Y5.3712 -G1 X1.4991 Y5.2379 -G3 X1.496 Y5.2186 I0.0594 J-0.0193 -G3 X1.5953 Y5.1681 I0.0625 J0 -G1 X1.7087 Y5.2505 -G1 X1.822 Y5.1681 -G3 X1.9213 Y5.2186 I0.0367 J0.0506 -G3 X1.9182 Y5.238 I-0.0625 J0 -G1 X1.8748 Y5.3712 -G1 X1.9882 Y5.4536 -G3 X2.014 Y5.5042 I-0.0367 J0.0506 -G3 X1.9515 Y5.5667 I-0.0625 J0 -G1 X1.8093 Y5.5667 -G0 Z0.25 -G0 X1.8994 Y5.7365 -G1 Z-0.05 F30 -G1 X1.8448 Y5.7761 F10 -G2 X1.8322 Y5.7863 I0.0955 J0.1315 -G2 X1.8639 Y5.7286 I-0.1235 J-0.1056 -G1 X1.88 Y5.6766 -G1 X1.8994 Y5.7365 -G0 Z0.25 -G0 X1.9582 Y5.7556 -G1 Z-0.05 F30 -G1 X1.8742 Y5.8166 F10 -G2 X1.8278 Y5.9076 I0.0661 J0.091 -G2 X1.8283 Y5.9181 I0.1125 J0 -G2 X1.7926 Y5.9353 I0.0305 J0.1083 -G1 X1.7087 Y5.9964 -G1 X1.6247 Y5.9353 -G2 X1.5889 Y5.918 I-0.0661 J0.091 -G2 X1.5894 Y5.9076 I-0.112 J-0.0104 -G2 X1.543 Y5.8166 I-0.1125 J0 -G1 X1.4591 Y5.7556 -G1 X1.4912 Y5.6569 -G2 X1.4967 Y5.6221 I-0.107 J-0.0348 -G2 X1.4965 Y5.6167 I-0.1125 J0 -G1 X1.5695 Y5.6167 -G1 X1.6017 Y5.7155 -G2 X1.8162 Y5.7139 I0.107 J-0.0348 -G1 X1.8462 Y5.6167 -G1 X1.9208 Y5.6167 -G2 X1.9206 Y5.6221 I0.1124 J0.0054 -G2 X1.9261 Y5.6568 I0.1125 J0 -G1 X1.9582 Y5.7556 -G0 Z0.25 -G0 X1.6001 Y5.8016 -G1 Z-0.05 F30 -G2 X1.8168 Y5.802 I0.1086 J-0.1209 F10 -G2 X1.7795 Y5.8845 I0.1235 J0.1056 -G2 X1.7632 Y5.8949 I0.0793 J0.1418 -G1 X1.7087 Y5.9346 -G1 X1.6541 Y5.8949 -G2 X1.6377 Y5.8844 I-0.0955 J0.1315 -G2 X1.6001 Y5.8016 I-0.1608 J0.0232 -G2 X1.5855 Y5.7867 I-0.1232 J0.106 -G2 X1.6001 Y5.8016 I0.1232 J-0.106 -G0 Z0.25 -G0 X1.3347 Y5.9701 -G1 Z-0.05 F30 -G1 X1.2938 Y6.1025 F10 -G3 X1.1746 Y6.1034 I-0.0597 J-0.0184 -G1 X1.1313 Y5.9701 -G1 X0.9912 Y5.9701 -G3 X0.9287 Y5.9076 I0 J-0.0625 -G3 X0.9544 Y5.857 I0.0625 J0 -G1 X1.0678 Y5.7747 -G1 X1.0244 Y5.6414 -G3 X1.0214 Y5.6221 I0.0594 J-0.0193 -G3 X1.1206 Y5.5715 I0.0625 J0 -G1 X1.2341 Y5.6539 -G1 X1.3474 Y5.5715 -G3 X1.4467 Y5.6221 I0.0367 J0.0506 -G3 X1.4436 Y5.6414 I-0.0625 J0 -G1 X1.4003 Y5.7747 -G1 X1.5136 Y5.857 -G3 X1.5394 Y5.9076 I-0.0367 J0.0506 -G3 X1.4769 Y5.9701 I-0.0625 J0 -G1 X1.3347 Y5.9701 -G0 Z0.25 -G0 X1.3525 Y6.1953 -G1 Z-0.05 F30 -G2 X1.3893 Y6.132 I-0.1185 J-0.1112 F10 -G1 X1.4053 Y6.0804 -G1 X1.4248 Y6.1407 -G1 X1.3702 Y6.1804 -G2 X1.3525 Y6.1953 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.3996 Y6.2209 -G1 Z-0.05 F30 -G2 X1.3532 Y6.3119 I0.0661 J0.091 F10 -G2 X1.3537 Y6.3224 I0.1125 J0 -G2 X1.3181 Y6.3397 I0.0304 J0.1083 -G1 X1.234 Y6.4007 -G1 X1.15 Y6.3397 -G2 X1.1143 Y6.3224 I-0.0661 J0.091 -G2 X1.1148 Y6.3119 I-0.112 J-0.0106 -G2 X1.0684 Y6.2209 I-0.1125 J0 -G1 X0.9844 Y6.1598 -G1 X1.0165 Y6.0611 -G2 X1.022 Y6.0264 I-0.107 J-0.0347 -G2 X1.0218 Y6.0201 I-0.1125 J0 -G1 X1.095 Y6.0201 -G1 X1.1271 Y6.1189 -G2 X1.3416 Y6.1172 I0.107 J-0.0348 -G1 X1.3716 Y6.0201 -G1 X1.4462 Y6.0201 -G2 X1.446 Y6.0264 I0.1123 J0.0062 -G2 X1.4515 Y6.0611 I0.1125 J0 -G1 X1.4836 Y6.1598 -G1 X1.3996 Y6.2209 -G0 Z0.25 -G0 X1.1192 Y6.199 -G1 Z-0.05 F30 -G2 X1.3473 Y6.2007 I0.1148 J-0.115 F10 -G2 X1.3049 Y6.2889 I0.1185 J0.1112 -G2 X1.2887 Y6.2992 I0.0793 J0.1418 -G1 X1.234 Y6.339 -G1 X1.1794 Y6.2993 -G2 X1.1632 Y6.2889 I-0.0955 J0.1315 -G2 X1.1192 Y6.199 I-0.1609 J0.023 -G2 X1.1171 Y6.1969 I-0.1169 J0.1129 -G2 X1.1192 Y6.199 I0.1169 J-0.1129 -G0 Z0.25 -G0 X1.6622 Y3.5986 -G1 Z-0.05 F30 -G1 X1.7552 Y3.5986 F10 -G1 X1.7087 Y3.6324 -G1 X1.6622 Y3.5986 -G0 Z0.25 -G0 X2.1135 Y3.7486 -G1 Z-0.05 F30 -G1 X2.253 Y3.7486 F10 -G2 X2.2095 Y3.8322 I0.162 J0.1375 -G2 X2.2084 Y3.833 I0.1239 J0.1727 -G1 X2.1832 Y3.8513 -G1 X2.158 Y3.833 -G2 X2.157 Y3.8322 I-0.1249 J0.1719 -G2 X2.1135 Y3.7486 I-0.2055 J0.0539 -G1 X2.047 Y3.7547 F10 -G1 X1.9924 Y3.715 F10 -G1 X1.9978 Y3.6986 -G1 X2.3687 Y3.6986 -G1 X2.3741 Y3.715 -G1 X2.3195 Y3.7547 -G2 X2.2542 Y3.863 I0.0955 J0.1315 -G2 X2.2378 Y3.8734 I0.0792 J0.1419 -G1 X2.1832 Y3.9131 -G1 X2.1286 Y3.8734 -G2 X2.1123 Y3.863 I-0.0955 J0.1315 -G2 X2.047 Y3.7547 I-0.1608 J0.0232 -G1 X2.0176 Y3.7951 F10 -G1 X1.9336 Y3.7341 F10 -G1 X1.9614 Y3.6486 -G1 X2.405 Y3.6486 -G1 X2.4328 Y3.7341 -G1 X2.3489 Y3.7951 -G2 X2.3025 Y3.8861 I0.0661 J0.091 -G2 X2.303 Y3.8966 I0.1125 J0 -G2 X2.2672 Y3.9139 I0.0303 J0.1083 -G1 X2.1832 Y3.9749 -G1 X2.0993 Y3.9139 -G2 X2.0635 Y3.8966 I-0.0661 J0.091 -G2 X2.064 Y3.8861 I-0.112 J-0.0104 -G2 X2.0176 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X2.6113 Y3.5986 -G1 Z-0.05 F30 -G1 X2.7043 Y3.5986 F10 -G1 X2.6578 Y3.6324 -G1 X2.6113 Y3.5986 -G0 Z0.25 -G0 X3.0628 Y3.7486 -G1 Z-0.05 F30 -G1 X3.2022 Y3.7486 F10 -G2 X3.1586 Y3.8323 I0.162 J0.1375 -G2 X3.1578 Y3.8329 I0.124 J0.1726 -G1 X3.1324 Y3.8513 -G1 X3.1072 Y3.833 -G2 X3.1063 Y3.8323 I-0.1249 J0.1719 -G2 X3.0628 Y3.7486 I-0.2056 J0.0538 -G1 X2.9963 Y3.7547 F10 -G1 X2.9416 Y3.715 F10 -G1 X2.9469 Y3.6986 -G1 X3.318 Y3.6986 -G1 X3.3233 Y3.715 -G1 X3.2687 Y3.7547 -G2 X3.2033 Y3.8631 I0.0955 J0.1315 -G2 X3.1871 Y3.8734 I0.0793 J0.1418 -G1 X3.1324 Y3.9131 -G1 X3.0778 Y3.8734 -G2 X3.0616 Y3.8631 I-0.0955 J0.1315 -G2 X2.9963 Y3.7547 I-0.1609 J0.0231 -G1 X2.9669 Y3.7951 F10 -G1 X2.8829 Y3.7341 F10 -G1 X2.9106 Y3.6486 -G1 X3.3543 Y3.6486 -G1 X3.382 Y3.7341 -G1 X3.298 Y3.7951 -G2 X3.2517 Y3.8861 I0.0661 J0.091 -G2 X3.2522 Y3.8966 I0.1125 J0 -G2 X3.2165 Y3.9139 I0.0305 J0.1083 -G1 X3.1324 Y3.9749 -G1 X3.0484 Y3.9139 -G2 X3.0127 Y3.8966 I-0.0661 J0.091 -G2 X3.0132 Y3.8861 I-0.112 J-0.0104 -G2 X2.9669 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X2.8235 Y4.1994 -G1 Z-0.05 F30 -G2 X2.7771 Y4.2904 I0.0661 J0.091 F10 -G2 X2.7776 Y4.3008 I0.1125 J0 -G2 X2.7418 Y4.3182 I0.0303 J0.1083 -G1 X2.6578 Y4.3792 -G1 X2.5738 Y4.3182 -G2 X2.5382 Y4.3009 I-0.0661 J0.091 -G2 X2.5387 Y4.2904 I-0.112 J-0.0104 -G2 X2.4923 Y4.1994 I-0.1125 J0 -G1 X2.4083 Y4.1384 -G1 X2.4403 Y4.0396 -G2 X2.4458 Y4.0049 I-0.107 J-0.0347 -G2 X2.4457 Y3.9986 I-0.1125 J0 -G1 X2.5188 Y3.9986 -G1 X2.5508 Y4.0973 -G2 X2.7653 Y4.0958 I0.107 J-0.0347 -G1 X2.7954 Y3.9986 -G1 X2.87 Y3.9986 -G2 X2.8698 Y4.0049 I0.1123 J0.0062 -G2 X2.8753 Y4.0397 I0.1125 J0 -G1 X2.9074 Y4.1384 -G1 X2.8235 Y4.1994 -G0 Z0.25 -G0 X2.7747 Y4.1755 -G1 Z-0.05 F30 -G2 X2.8131 Y4.1106 I-0.1169 J-0.1129 F10 -G1 X2.829 Y4.059 -G1 X2.8486 Y4.1193 -G1 X2.7941 Y4.159 -G2 X2.7747 Y4.1755 I0.0955 J0.1315 -G0 Z0.25 -G0 X2.5446 Y4.1792 -G1 Z-0.05 F30 -G2 X2.7727 Y4.1776 I0.1132 J-0.1166 F10 -G2 X2.7287 Y4.2673 I0.1169 J0.1129 -G2 X2.7124 Y4.2777 I0.0792 J0.1419 -G1 X2.6578 Y4.3174 -G1 X2.6032 Y4.2777 -G2 X2.587 Y4.2673 I-0.0955 J0.1315 -G2 X2.5446 Y4.1792 I-0.1609 J0.0231 -G2 X2.5393 Y4.1738 I-0.1185 J0.1112 -G2 X2.5446 Y4.1792 I0.1185 J-0.1112 -G0 Z0.25 -G0 X3.5606 Y3.5986 -G1 Z-0.05 F30 -G1 X3.6536 Y3.5986 F10 -G1 X3.6071 Y3.6324 -G1 X3.5606 Y3.5986 -G0 Z0.25 -G0 X4.1823 Y6.7787 -G1 Z-0.05 F30 -G1 X4.1414 Y6.9112 F10 -G3 X4.0222 Y6.912 I-0.0597 J-0.0185 -G1 X3.979 Y6.7787 -G1 X3.8388 Y6.7787 -G3 X3.7763 Y6.7162 I0 J-0.0625 -G3 X3.802 Y6.6657 I0.0625 J0 -G1 X3.9154 Y6.5833 -G1 X3.8721 Y6.45 -G3 X3.8691 Y6.4307 I0.0594 J-0.0193 -G3 X3.9683 Y6.3802 I0.0625 J0 -G1 X4.0817 Y6.4625 -G1 X4.195 Y6.3802 -G3 X4.2943 Y6.4307 I0.0367 J0.0506 -G3 X4.2912 Y6.45 I-0.0625 J0 -G1 X4.248 Y6.5833 -G1 X4.3613 Y6.6657 -G3 X4.3871 Y6.7162 I-0.0367 J0.0506 -G3 X4.3246 Y6.7787 I-0.0625 J0 -G1 X4.1823 Y6.7787 -G0 Z0.25 -G0 X4.4415 Y6.6034 -G1 Z-0.05 F30 -G2 X4.7115 Y6.5364 I0.1147 J-0.1151 F10 -G1 X4.7274 Y6.4848 -G1 X4.7471 Y6.5451 -G1 X4.6925 Y6.5848 -G2 X4.6271 Y6.694 I0.0955 J0.1315 -G2 X4.6108 Y6.7044 I0.0793 J0.1418 -G1 X4.5563 Y6.744 -G1 X4.5017 Y6.7044 -G2 X4.4856 Y6.6941 I-0.0955 J0.1315 -G2 X4.4415 Y6.6034 I-0.161 J0.0222 -G2 X4.4393 Y6.6012 I-0.1169 J0.1129 -G2 X4.4415 Y6.6034 I0.1169 J-0.1129 -G1 X4.3907 Y6.6252 F10 -G1 X4.3067 Y6.5642 F10 -G1 X4.3388 Y6.4655 -G2 X4.3443 Y6.4307 I-0.107 J-0.0347 -G2 X4.3441 Y6.4244 I-0.1125 J0 -G1 X4.4172 Y6.4244 -G1 X4.4493 Y6.5231 -G2 X4.6637 Y6.5216 I0.107 J-0.0347 -G1 X4.6938 Y6.4244 -G1 X4.7684 Y6.4244 -G2 X4.7682 Y6.4307 I0.1123 J0.0064 -G2 X4.7738 Y6.4655 I0.1125 J0 -G1 X4.8059 Y6.5642 -G1 X4.7219 Y6.6252 -G2 X4.6755 Y6.7162 I0.0661 J0.091 -G2 X4.6761 Y6.7275 I0.1125 J0 -G2 X4.6402 Y6.7448 I0.0303 J0.1084 -G1 X4.5563 Y6.8058 -G1 X4.4723 Y6.7448 -G2 X4.4365 Y6.7275 I-0.0661 J0.091 -G2 X4.4371 Y6.7162 I-0.1119 J-0.0113 -G2 X4.3907 Y6.6252 I-0.1125 J0 -G0 Z0.25 -G0 X4.6569 Y6.3744 -G1 Z-0.05 F30 -G1 X4.616 Y6.5068 F10 -G3 X4.4968 Y6.5076 I-0.0597 J-0.0185 -G1 X4.4535 Y6.3744 -G1 X4.3134 Y6.3744 -G3 X4.2509 Y6.3119 I0 J-0.0625 -G3 X4.2767 Y6.2613 I0.0625 J0 -G1 X4.3901 Y6.1789 -G1 X4.3467 Y6.0457 -G3 X4.3437 Y6.0264 I0.0594 J-0.0193 -G3 X4.4429 Y5.9758 I0.0625 J0 -G1 X4.5563 Y6.0582 -G1 X4.6696 Y5.9758 -G3 X4.7689 Y6.0264 I0.0367 J0.0506 -G3 X4.7658 Y6.0457 I-0.0625 J0 -G1 X4.7225 Y6.1789 -G1 X4.8359 Y6.2613 -G3 X4.8617 Y6.3119 I-0.0367 J0.0506 -G3 X4.7992 Y6.3744 I-0.0625 J0 -G1 X4.6569 Y6.3744 -G0 Z0.25 -G0 X4.9177 Y6.2007 -G1 Z-0.05 F30 -G2 X5.1457 Y6.199 I0.1132 J-0.1166 F10 -G2 X5.1017 Y6.2889 I0.1169 J0.1129 -G2 X5.0856 Y6.2992 I0.0793 J0.1418 -G1 X5.0309 Y6.339 -G1 X4.9763 Y6.2993 -G2 X4.96 Y6.2889 I-0.0955 J0.1315 -G2 X4.9177 Y6.2007 I-0.1609 J0.023 -G2 X4.9124 Y6.1953 I-0.1185 J0.1112 -G2 X4.9177 Y6.2007 I0.1185 J-0.1112 -G0 Z0.25 -G0 X5.1478 Y6.1969 -G1 Z-0.05 F30 -G2 X5.1861 Y6.1321 I-0.1169 J-0.1129 F10 -G1 X5.2021 Y6.0803 -G1 X5.2217 Y6.1407 -G1 X5.1671 Y6.1804 -G2 X5.1478 Y6.1969 I0.0955 J0.1315 -G0 Z0.25 -G0 X5.1965 Y6.2209 -G1 Z-0.05 F30 -G2 X5.1501 Y6.3119 I0.0661 J0.091 F10 -G2 X5.1506 Y6.3224 I0.1125 J0 -G2 X5.115 Y6.3397 I0.0304 J0.1083 -G1 X5.0309 Y6.4007 -G1 X4.9469 Y6.3397 -G2 X4.9112 Y6.3224 I-0.0661 J0.091 -G2 X4.9117 Y6.3119 I-0.112 J-0.0106 -G2 X4.8653 Y6.2209 I-0.1125 J0 -G1 X4.7813 Y6.1598 -G1 X4.8134 Y6.0611 -G2 X4.8189 Y6.0264 I-0.107 J-0.0347 -G2 X4.8187 Y6.0201 I-0.1125 J0 -G1 X4.8918 Y6.0201 -G1 X4.9238 Y6.1188 -G2 X5.1383 Y6.1173 I0.107 J-0.0347 -G1 X5.1684 Y6.0201 -G1 X5.2431 Y6.0201 -G2 X5.2429 Y6.0264 I0.1123 J0.0062 -G2 X5.2484 Y6.0611 I0.1125 J0 -G1 X5.2805 Y6.1598 -G1 X5.1965 Y6.2209 -G0 Z0.25 -G0 X5.1315 Y5.9701 -G1 Z-0.05 F30 -G1 X5.0905 Y6.1025 F10 -G3 X4.9714 Y6.1034 I-0.0597 J-0.0185 -G1 X4.9281 Y5.9701 -G1 X4.788 Y5.9701 -G3 X4.7255 Y5.9076 I0 J-0.0625 -G3 X4.7513 Y5.857 I0.0625 J0 -G1 X4.8646 Y5.7747 -G1 X4.8213 Y5.6414 -G3 X4.8182 Y5.6221 I0.0594 J-0.0193 -G3 X4.9175 Y5.5715 I0.0625 J0 -G1 X5.0309 Y5.6539 -G1 X5.1443 Y5.5715 -G3 X5.2435 Y5.6221 I0.0367 J0.0506 -G3 X5.2405 Y5.6414 I-0.0625 J0 -G1 X5.1971 Y5.7747 -G1 X5.3105 Y5.857 -G3 X5.3363 Y5.9076 I-0.0367 J0.0506 -G3 X5.2738 Y5.9701 I-0.0625 J0 -G1 X5.1315 Y5.9701 -G0 Z0.25 -G0 X5.3969 Y5.8016 -G1 Z-0.05 F30 -G2 X5.6608 Y5.7286 I0.1086 J-0.1209 F10 -G1 X5.6799 Y5.6667 -G1 X5.7239 Y5.6667 -G1 X5.7239 Y5.8789 -G2 X5.5601 Y5.8949 I-0.0682 J0.1475 -G1 X5.5055 Y5.9346 -G1 X5.4509 Y5.8949 -G2 X5.4346 Y5.8844 I-0.0955 J0.1315 -G2 X5.3969 Y5.8016 I-0.1608 J0.0232 -G2 X5.3823 Y5.7867 I-0.1232 J0.106 -G2 X5.3969 Y5.8016 I0.1232 J-0.106 -G1 X5.3399 Y5.8166 F10 -G1 X5.2559 Y5.7556 F10 -G1 X5.288 Y5.6569 -G2 X5.2935 Y5.6221 I-0.107 J-0.0348 -G2 X5.2934 Y5.6167 I-0.1125 J0 -G1 X5.3664 Y5.6167 -G1 X5.3985 Y5.7155 -G2 X5.613 Y5.7139 I0.107 J-0.0348 -G1 X5.643 Y5.6167 -G1 X5.7483 Y5.6167 -G2 X5.7739 Y5.6137 I0 J-0.1125 -G1 X5.7739 Y6.1914 -G1 X5.7305 Y6.1599 -G1 X5.7626 Y6.0612 -G2 X5.7681 Y6.0264 I-0.107 J-0.0348 -G2 X5.5895 Y5.9353 I-0.1125 J0 -G1 X5.5055 Y5.9964 -G1 X5.4216 Y5.9353 -G2 X5.3858 Y5.918 I-0.0661 J0.091 -G2 X5.3863 Y5.9076 I-0.112 J-0.0104 -G2 X5.3399 Y5.8166 I-0.1125 J0 -G0 Z0.25 -G0 X5.6061 Y5.5667 -G1 Z-0.05 F30 -G1 X5.5652 Y5.6992 F10 -G3 X5.4461 Y5.7001 I-0.0597 J-0.0184 -G1 X5.4027 Y5.5667 -G1 X5.2626 Y5.5667 -G3 X5.2001 Y5.5042 I0 J-0.0625 -G3 X5.2259 Y5.4536 I0.0625 J0 -G1 X5.3393 Y5.3712 -G1 X5.296 Y5.2379 -G3 X5.2929 Y5.2186 I0.0594 J-0.0193 -G3 X5.3922 Y5.1681 I0.0625 J0 -G1 X5.5055 Y5.2505 -G1 X5.6189 Y5.1681 -G3 X5.7181 Y5.2186 I0.0367 J0.0506 -G3 X5.7151 Y5.238 I-0.0625 J0 -G1 X5.6717 Y5.3712 -G1 X5.7851 Y5.4536 -G3 X5.8108 Y5.5042 I-0.0367 J0.0506 -G3 X5.7483 Y5.5667 I-0.0625 J0 -G1 X5.6061 Y5.5667 -G0 Z0.25 -G0 X5.6061 Y6.3744 -G1 Z-0.05 F30 -G1 X5.5652 Y6.5068 F10 -G3 X5.4461 Y6.5077 I-0.0597 J-0.0184 -G1 X5.4027 Y6.3744 -G1 X5.2626 Y6.3744 -G3 X5.2001 Y6.3119 I0 J-0.0625 -G3 X5.2259 Y6.2613 I0.0625 J0 -G1 X5.3393 Y6.1789 -G1 X5.296 Y6.0457 -G3 X5.2929 Y6.0264 I0.0594 J-0.0193 -G3 X5.3922 Y5.9758 I0.0625 J0 -G1 X5.5055 Y6.0582 -G1 X5.6189 Y5.9758 -G3 X5.7181 Y6.0264 I0.0367 J0.0506 -G3 X5.7151 Y6.0457 I-0.0625 J0 -G1 X5.6717 Y6.1789 -G1 X5.7851 Y6.2613 -G3 X5.8108 Y6.3119 I-0.0367 J0.0506 -G3 X5.7483 Y6.3744 I-0.0625 J0 -G1 X5.6061 Y6.3744 -G0 Z0.25 -G0 X5.351 Y6.5386 -G1 Z-0.05 F30 -G2 X5.6608 Y6.5363 I0.1545 J-0.0503 F10 -G1 X5.6799 Y6.4744 -G1 X5.7239 Y6.4744 -G1 X5.7239 Y6.6884 -G2 X5.5601 Y6.7044 I-0.0682 J0.1475 -G1 X5.5055 Y6.744 -G1 X5.4509 Y6.7044 -G2 X5.4347 Y6.694 I-0.0955 J0.1315 -G2 X5.3693 Y6.5848 I-0.161 J0.0223 -G1 X5.3147 Y6.5451 -G1 X5.3339 Y6.4861 -G1 X5.351 Y6.5386 -G1 X5.3985 Y6.5231 F10 -G2 X5.613 Y6.5215 I0.107 J-0.0348 F10 -G1 X5.643 Y6.4244 -G1 X5.7483 Y6.4244 -G2 X5.7739 Y6.4214 I0 J-0.1125 -G1 X5.7739 Y7.0008 -G1 X5.7305 Y6.9693 -G1 X5.7626 Y6.8706 -G2 X5.7681 Y6.8358 I-0.107 J-0.0348 -G2 X5.5895 Y6.7448 I-0.1125 J0 -G1 X5.5055 Y6.8058 -G1 X5.4216 Y6.7448 -G2 X5.3857 Y6.7275 I-0.0661 J0.091 -G2 X5.3863 Y6.7162 I-0.1119 J-0.0112 -G2 X5.3399 Y6.6252 I-0.1125 J0 -G1 X5.2559 Y6.5642 -G1 X5.288 Y6.4655 -G2 X5.2935 Y6.4307 I-0.107 J-0.0348 -G2 X5.2934 Y6.4244 I-0.1125 J0 -G1 X5.3664 Y6.4244 -G1 X5.3985 Y6.5231 -G0 Z0.25 -G0 X5.1315 Y6.7787 -G1 Z-0.05 F30 -G1 X5.0905 Y6.9112 F10 -G3 X4.9714 Y6.912 I-0.0597 J-0.0185 -G1 X4.9281 Y6.7787 -G1 X4.788 Y6.7787 -G3 X4.7255 Y6.7162 I0 J-0.0625 -G3 X4.7513 Y6.6657 I0.0625 J0 -G1 X4.8646 Y6.5833 -G1 X4.8213 Y6.4501 -G3 X4.8182 Y6.4307 I0.0594 J-0.0193 -G3 X4.9175 Y6.3802 I0.0625 J0 -G1 X5.0309 Y6.4625 -G1 X5.1443 Y6.3802 -G3 X5.2435 Y6.4307 I0.0367 J0.0506 -G3 X5.2405 Y6.4501 I-0.0625 J0 -G1 X5.1971 Y6.5833 -G1 X5.3105 Y6.6657 -G3 X5.3363 Y6.7162 I-0.0367 J0.0506 -G3 X5.2738 Y6.7787 I-0.0625 J0 -G1 X5.1315 Y6.7787 -G0 Z0.25 -G0 X5.0552 Y7.1674 -G1 Z-0.05 F30 -G1 X5.0066 Y7.1674 F10 -G2 X5.0117 Y7.1214 I-0.2075 J-0.046 -G2 X5.011 Y7.1043 I-0.2125 J0 -G2 X5.0508 Y7.1043 I0.0199 J-0.2116 -G2 X5.0501 Y7.1214 I0.2118 J0.0171 -G2 X5.0552 Y7.1674 I0.2125 J0 -G1 X5.1001 Y7.1214 F10 -G2 X5.1315 Y7.2174 I0.1625 J0 F10 -G1 X4.9303 Y7.2174 -G2 X4.9617 Y7.1214 I-0.1311 J-0.096 -G2 X4.8947 Y6.9899 I-0.1625 J0 -G1 X4.8401 Y6.9502 -G1 X4.8594 Y6.8908 -G1 X4.8763 Y6.9429 -G2 X5.1861 Y6.9407 I0.1546 J-0.0502 -G1 X5.202 Y6.8894 -G1 X5.2217 Y6.9502 -G1 X5.1671 Y6.9899 -G2 X5.1001 Y7.1214 I0.0955 J0.1315 -G1 X5.1501 Y7.1214 F10 -G2 X5.2626 Y7.2339 I0.1125 J0 F10 -G1 X5.3664 Y7.2339 -G1 X5.3773 Y7.2674 -G1 X4.6834 Y7.2674 -G1 X4.6938 Y7.2339 -G1 X4.7992 Y7.2339 -G2 X4.9117 Y7.1214 I0 J-0.1125 -G2 X4.8653 Y7.0303 I-0.1125 J0 -G1 X4.7813 Y6.9693 -G1 X4.8134 Y6.8706 -G2 X4.8189 Y6.8358 I-0.107 J-0.0347 -G2 X4.8186 Y6.8287 I-0.1125 J0 -G1 X4.8918 Y6.8287 -G1 X4.9238 Y6.9274 -G2 X5.1383 Y6.926 I0.107 J-0.0347 -G1 X5.1684 Y6.8287 -G1 X5.2431 Y6.8287 -G2 X5.2429 Y6.8358 I0.1123 J0.0071 -G2 X5.2484 Y6.8706 I0.1125 J0 -G1 X5.2805 Y6.9693 -G1 X5.1965 Y7.0303 -G2 X5.1501 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X5.7739 Y7.2674 -G1 Z-0.05 F30 -G1 X5.6327 Y7.2674 F10 -G1 X5.643 Y7.2339 -G1 X5.7483 Y7.2339 -G2 X5.7739 Y7.2309 I0 J-0.1125 -G1 X5.7739 Y7.2674 -G0 Z0.25 -G0 X4.106 Y7.1674 -G1 Z-0.05 F30 -G1 X4.0574 Y7.1674 F10 -G2 X4.0624 Y7.1214 I-0.2075 J-0.046 -G2 X4.0617 Y7.1043 I-0.2125 J0 -G2 X4.1016 Y7.1043 I0.02 J-0.2116 -G2 X4.1009 Y7.1214 I0.2118 J0.0171 -G2 X4.106 Y7.1674 I0.2125 J0 -G1 X4.1509 Y7.1214 F10 -G2 X4.1824 Y7.2174 I0.1625 J0 F10 -G1 X3.981 Y7.2174 -G2 X4.0124 Y7.1214 I-0.1311 J-0.096 -G2 X3.9454 Y6.9899 I-0.1625 J0 -G1 X3.8909 Y6.9502 -G1 X3.9102 Y6.8908 -G1 X3.9271 Y6.9429 -G2 X4.2369 Y6.9407 I0.1546 J-0.0502 -G1 X4.2527 Y6.8896 -G1 X4.2725 Y6.9502 -G1 X4.2179 Y6.9899 -G2 X4.1509 Y7.1214 I0.0955 J0.1315 -G1 X4.2009 Y7.1214 F10 -G2 X4.3134 Y7.2339 I0.1125 J0 F10 -G1 X4.4172 Y7.2339 -G1 X4.4281 Y7.2674 -G1 X3.7342 Y7.2674 -G1 X3.7446 Y7.2339 -G1 X3.8499 Y7.2339 -G2 X3.9624 Y7.1214 I0 J-0.1125 -G2 X3.916 Y7.0303 I-0.1125 J0 -G1 X3.8321 Y6.9693 -G1 X3.8642 Y6.8706 -G2 X3.8697 Y6.8358 I-0.107 J-0.0348 -G2 X3.8695 Y6.8287 I-0.1125 J0 -G1 X3.9426 Y6.8287 -G1 X3.9747 Y6.9274 -G2 X4.1891 Y6.926 I0.107 J-0.0347 -G1 X4.2192 Y6.8287 -G1 X4.2939 Y6.8287 -G2 X4.2937 Y6.8358 I0.1123 J0.0071 -G2 X4.2992 Y6.8706 I0.1125 J0 -G1 X4.3313 Y6.9693 -G1 X4.2473 Y7.0303 -G2 X4.2009 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X0.2848 Y0.5504 -G1 Z-0.0625 F30 -G1 X14.5348 Y0.5504 F10 -G1 X14.5348 Y-0.0264 -G1 X0.2848 Y-0.0264 -G1 X0.2848 Y0.5504 -G0 Z0.25 -G0 X0.2848 Y1.1275 -G1 Z-0.0625 F30 -G1 X14.5348 Y1.1275 F10 -G1 X14.5348 Y0.5508 -G1 X0.2848 Y0.5508 -G1 X0.2848 Y1.1275 -G0 Z0.25 -G0 X0.2848 Y1.7049 -G1 Z-0.0625 F30 -G1 X14.5348 Y1.7049 F10 -G1 X14.5348 Y1.1281 -G1 X0.2848 Y1.1281 -G1 X0.2848 Y1.7049 -G0 Z0.25 -G0 X0.2848 Y2.282 -G1 Z-0.0625 F30 -G1 X14.5348 Y2.282 F10 -G1 X14.5348 Y1.7053 -G1 X0.2848 Y1.7053 -G1 X0.2848 Y2.282 -G0 Z0.25 -G0 X0.2848 Y2.8592 -G1 Z-0.0625 F30 -G1 X14.5348 Y2.8592 F10 -G1 X14.5348 Y2.2824 -G1 X0.2848 Y2.2824 -G1 X0.2848 Y2.8592 -G0 Z0.25 -G0 X0.2848 Y3.4363 -G1 Z-0.0625 F30 -G1 X14.5348 Y3.4363 F10 -G1 X14.5348 Y2.8596 -G1 X0.2848 Y2.8596 -G1 X0.2848 Y3.4363 -G0 Z0.25 -G0 X0.2848 Y7.4736 -G1 Z-0.0625 F30 -G1 X5.9848 Y7.4736 F10 -G1 X5.9848 Y3.4349 -G1 X0.2848 Y3.4349 -G1 X0.2848 Y7.4736 - -(profile 3) -G0 Z0.25 -T0 M6 -G0 X5.9859 Y7.4764 -G1 Z-0.0625 F30 -G1 X14.5348 Y7.4764 F10 -G1 X14.5348 Y6.8996 -G1 X5.9859 Y6.8996 -G1 X5.9859 Y7.4764 -G0 Z0.25 -G0 X5.9859 Y6.8992 -G1 Z-0.0625 F30 -G1 X14.5348 Y6.8992 F10 -G1 X14.5348 Y6.3225 -G1 X5.9859 Y6.3225 -G1 X5.9859 Y6.8992 -G0 Z0.25 -G0 X5.9859 Y6.3221 -G1 Z-0.0625 F30 -G1 X14.5348 Y6.3221 F10 -G1 X14.5348 Y5.7453 -G1 X5.9859 Y5.7453 -G1 X5.9859 Y6.3221 -G0 Z0.25 -G0 X5.9859 Y5.7447 -G1 Z-0.0625 F30 -G1 X14.5348 Y5.7447 F10 -G1 X14.5348 Y5.168 -G1 X5.9859 Y5.168 -G1 X5.9859 Y5.7447 -G0 Z0.25 -G0 X5.9859 Y5.1676 -G1 Z-0.0625 F30 -G1 X14.5348 Y5.1676 F10 -G1 X14.5348 Y4.5908 -G1 X5.9859 Y4.5908 -G1 X5.9859 Y5.1676 -G0 Z0.25 -G0 X5.9859 Y4.5908 -G1 Z-0.0625 F30 -G1 X14.5348 Y4.5908 F10 -G1 X14.5348 Y4.0141 -G1 X5.9859 Y4.0141 -G1 X5.9859 Y4.5908 -G0 Z0.25 -G0 X5.9859 Y4.0137 -G1 Z-0.0625 F30 -G1 X14.5348 Y4.0137 F10 -G1 X14.5348 Y3.4369 -G1 X5.9859 Y3.4369 -G1 X5.9859 Y4.0137 -G0 Z0.25 -G0 X0.0973 Y-0.3389 -G1 Z-0.15 F30 -G1 X12.9877 Y-0.3389 F20 -G1 X13.4877 Y-0.3389 -G1 X14.7223 Y-0.3389 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 X7.2382 Y7.7861 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 X-0.0277 Y1.0339 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.3 F30 -G1 X12.9877 Y-0.3389 F20 -G1 X13.4877 Y-0.3389 -G1 X14.7223 Y-0.3389 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 X7.2382 Y7.7861 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 X-0.0277 Y1.0339 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.45 F30 -G1 X12.9877 Y-0.3389 F20 -G1 X13.4877 Y-0.3389 -G1 X14.7223 Y-0.3389 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 X7.2382 Y7.7861 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 X-0.0277 Y1.0339 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.6 F30 -G1 X12.9877 Y-0.3389 F20 -G1 X13.4877 Y-0.3389 -G1 X14.7223 Y-0.3389 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 X7.2382 Y7.7861 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 X-0.0277 Y1.0339 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.75 F30 -G1 X12.9877 Y-0.3389 F20 -G1 Z-0.6 F30 -G1 X13.4877 Y-0.3389 F20 -G1 Z-0.75 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 Z-0.6 F30 -G1 X7.2382 Y7.7861 F20 -G1 Z-0.75 F30 -G1 X0.0973 Y7.7861 F20 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 Z-0.6 F30 -G1 X-0.0277 Y1.0339 F20 -G1 Z-0.75 F30 -G1 X-0.0277 Y-0.2139 F20 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.85 F30 -G1 X12.9877 Y-0.3389 F20 -G1 Z-0.6 F30 -G1 X13.4877 Y-0.3389 F20 -G1 Z-0.85 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 Z-0.6 F30 -G1 X7.2382 Y7.7861 F20 -G1 Z-0.85 F30 -G1 X0.0973 Y7.7861 F20 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 Z-0.6 F30 -G1 X-0.0277 Y1.0339 F20 -G1 Z-0.85 F30 -G1 X-0.0277 Y-0.2139 F20 -G3 X0.0973 Y-0.3389 I0.125 J0 -G0 Z0.25 -M5 -M30 diff --git a/gcode/flag5-a-outline.nc b/gcode/flag5-a-outline.nc deleted file mode 100644 index aad09659..00000000 --- a/gcode/flag5-a-outline.nc +++ /dev/null @@ -1,67 +0,0 @@ -(Generated by PartKam Version 0.05) - -G20 G90 G40 - -(profile 3) -G0 Z0.25 -T0 M6 -G17 -M3 -G0 X0.0973 Y-0.3389 -G1 Z-0.15 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.3 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.45 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.6 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.75 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.85 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G0 Z0.25 -M5 -M30 diff --git a/gcode/flag5-a.nc b/gcode/flag5-a.nc deleted file mode 100644 index 9d8cf332..00000000 --- a/gcode/flag5-a.nc +++ /dev/null @@ -1,3360 +0,0 @@ -(Generated by PartKam Version 0.05) - -G20 G90 G40 - -(pocket 1) -G0 Z0.25 -T1 M6 -G17 -M3 -G0 X5.1315 Y4.3529 -G1 Z-0.05 F30 -G1 X5.0905 Y4.4853 F10 -G3 X4.9714 Y4.4862 I-0.0597 J-0.0185 -G1 X4.9281 Y4.3529 -G1 X4.788 Y4.3529 -G3 X4.7255 Y4.2904 I0 J-0.0625 -G3 X4.7513 Y4.2399 I0.0625 J0 -G1 X4.8646 Y4.1575 -G1 X4.8213 Y4.0242 -G3 X4.8182 Y4.0049 I0.0594 J-0.0193 -G3 X4.9175 Y3.9543 I0.0625 J0 -G1 X5.0309 Y4.0367 -G1 X5.1443 Y3.9543 -G3 X5.2435 Y4.0049 I0.0367 J0.0506 -G3 X5.2405 Y4.0242 I-0.0625 J0 -G1 X5.1971 Y4.1575 -G1 X5.3105 Y4.2399 -G3 X5.3363 Y4.2904 I-0.0367 J0.0506 -G3 X5.2738 Y4.3529 I-0.0625 J0 -G1 X5.1315 Y4.3529 -G0 Z0.25 -G0 X5.1315 Y5.9701 -G1 Z-0.05 F30 -G1 X5.0905 Y6.1025 F10 -G3 X4.9714 Y6.1034 I-0.0597 J-0.0185 -G1 X4.9281 Y5.9701 -G1 X4.788 Y5.9701 -G3 X4.7255 Y5.9076 I0 J-0.0625 -G3 X4.7513 Y5.857 I0.0625 J0 -G1 X4.8646 Y5.7747 -G1 X4.8213 Y5.6414 -G3 X4.8182 Y5.6221 I0.0594 J-0.0193 -G3 X4.9175 Y5.5715 I0.0625 J0 -G1 X5.0309 Y5.6539 -G1 X5.1443 Y5.5715 -G3 X5.2435 Y5.6221 I0.0367 J0.0506 -G3 X5.2405 Y5.6414 I-0.0625 J0 -G1 X5.1971 Y5.7747 -G1 X5.3105 Y5.857 -G3 X5.3363 Y5.9076 I-0.0367 J0.0506 -G3 X5.2738 Y5.9701 I-0.0625 J0 -G1 X5.1315 Y5.9701 -G0 Z0.25 -G0 X4.6569 Y4.7572 -G1 Z-0.05 F30 -G1 X4.616 Y4.8896 F10 -G3 X4.4968 Y4.8904 I-0.0597 J-0.0185 -G1 X4.4535 Y4.7572 -G1 X4.3134 Y4.7572 -G3 X4.2509 Y4.6947 I0 J-0.0625 -G3 X4.2767 Y4.6441 I0.0625 J0 -G1 X4.3901 Y4.5618 -G1 X4.3467 Y4.4285 -G3 X4.3437 Y4.4092 I0.0594 J-0.0193 -G3 X4.4429 Y4.3586 I0.0625 J0 -G1 X4.5563 Y4.441 -G1 X4.6696 Y4.3586 -G3 X4.7689 Y4.4092 I0.0367 J0.0506 -G3 X4.7658 Y4.4285 I-0.0625 J0 -G1 X4.7225 Y4.5617 -G1 X4.8359 Y4.6441 -G3 X4.8617 Y4.6947 I-0.0367 J0.0506 -G3 X4.7992 Y4.7572 I-0.0625 J0 -G1 X4.6569 Y4.7572 -G0 Z0.25 -G0 X3.2331 Y6.7787 -G1 Z-0.05 F30 -G1 X3.1921 Y6.9112 F10 -G3 X3.073 Y6.912 I-0.0597 J-0.0185 -G1 X3.0297 Y6.7787 -G1 X2.8896 Y6.7787 -G3 X2.8271 Y6.7162 I0 J-0.0625 -G3 X2.8529 Y6.6657 I0.0625 J0 -G1 X2.9662 Y6.5833 -G1 X2.9229 Y6.4501 -G3 X2.9198 Y6.4307 I0.0594 J-0.0193 -G3 X3.019 Y6.3802 I0.0625 J0 -G1 X3.1324 Y6.4625 -G1 X3.2459 Y6.3802 -G3 X3.3451 Y6.4307 I0.0367 J0.0506 -G3 X3.342 Y6.4501 I-0.0625 J0 -G1 X3.2987 Y6.5833 -G1 X3.4121 Y6.6657 -G3 X3.4378 Y6.7162 I-0.0367 J0.0506 -G3 X3.3753 Y6.7787 I-0.0625 J0 -G1 X3.2331 Y6.7787 -G0 Z0.25 -G0 X4.1823 Y4.3529 -G1 Z-0.05 F30 -G1 X4.1414 Y4.4853 F10 -G3 X4.0222 Y4.4862 I-0.0597 J-0.0185 -G1 X3.979 Y4.3529 -G1 X3.8388 Y4.3529 -G3 X3.7763 Y4.2904 I0 J-0.0625 -G3 X3.802 Y4.2399 I0.0625 J0 -G1 X3.9154 Y4.1575 -G1 X3.8721 Y4.0242 -G3 X3.8691 Y4.0049 I0.0594 J-0.0193 -G3 X3.9683 Y3.9543 I0.0625 J0 -G1 X4.0817 Y4.0367 -G1 X4.195 Y3.9543 -G3 X4.2943 Y4.0049 I0.0367 J0.0506 -G3 X4.2912 Y4.0242 I-0.0625 J0 -G1 X4.248 Y4.1575 -G1 X4.3613 Y4.2399 -G3 X4.3871 Y4.2904 I-0.0367 J0.0506 -G3 X4.3246 Y4.3529 I-0.0625 J0 -G1 X4.1823 Y4.3529 -G0 Z0.25 -G0 X3.2331 Y5.1616 -G1 Z-0.05 F30 -G1 X3.1921 Y5.294 F10 -G3 X3.073 Y5.2948 I-0.0597 J-0.0185 -G1 X3.0297 Y5.1616 -G1 X2.8896 Y5.1616 -G3 X2.8271 Y5.0991 I0 J-0.0625 -G3 X2.8529 Y5.0485 I0.0625 J0 -G1 X2.9662 Y4.9661 -G1 X2.9229 Y4.8329 -G3 X2.9198 Y4.8135 I0.0594 J-0.0193 -G3 X3.019 Y4.763 I0.0625 J0 -G1 X3.1324 Y4.8454 -G1 X3.2459 Y4.763 -G3 X3.3451 Y4.8135 I0.0367 J0.0506 -G3 X3.342 Y4.8329 I-0.0625 J0 -G1 X3.2987 Y4.9661 -G1 X3.4121 Y5.0485 -G3 X3.4378 Y5.0991 I-0.0367 J0.0506 -G3 X3.3753 Y5.1616 I-0.0625 J0 -G1 X3.2331 Y5.1616 -G0 Z0.25 -G0 X2.7585 Y6.3744 -G1 Z-0.05 F30 -G1 X2.7175 Y6.5068 F10 -G3 X2.5984 Y6.5076 I-0.0597 J-0.0185 -G1 X2.5551 Y6.3744 -G1 X2.415 Y6.3744 -G3 X2.3525 Y6.3119 I0 J-0.0625 -G3 X2.3783 Y6.2613 I0.0625 J0 -G1 X2.4916 Y6.1789 -G1 X2.4483 Y6.0457 -G3 X2.4452 Y6.0264 I0.0594 J-0.0193 -G3 X2.5445 Y5.9758 I0.0625 J0 -G1 X2.6578 Y6.0582 -G1 X2.7712 Y5.9758 -G3 X2.8704 Y6.0264 I0.0367 J0.0506 -G3 X2.8674 Y6.0457 I-0.0625 J0 -G1 X2.8241 Y6.1789 -G1 X2.9375 Y6.2613 -G3 X2.9632 Y6.3119 I-0.0367 J0.0506 -G3 X2.9007 Y6.3744 I-0.0625 J0 -G1 X2.7585 Y6.3744 -G0 Z0.25 -G0 X4.1823 Y6.7787 -G1 Z-0.05 F30 -G1 X4.1414 Y6.9112 F10 -G3 X4.0222 Y6.912 I-0.0597 J-0.0185 -G1 X3.979 Y6.7787 -G1 X3.8388 Y6.7787 -G3 X3.7763 Y6.7162 I0 J-0.0625 -G3 X3.802 Y6.6657 I0.0625 J0 -G1 X3.9154 Y6.5833 -G1 X3.8721 Y6.45 -G3 X3.8691 Y6.4307 I0.0594 J-0.0193 -G3 X3.9683 Y6.3802 I0.0625 J0 -G1 X4.0817 Y6.4625 -G1 X4.195 Y6.3802 -G3 X4.2943 Y6.4307 I0.0367 J0.0506 -G3 X4.2912 Y6.45 I-0.0625 J0 -G1 X4.248 Y6.5833 -G1 X4.3613 Y6.6657 -G3 X4.3871 Y6.7162 I-0.0367 J0.0506 -G3 X4.3246 Y6.7787 I-0.0625 J0 -G1 X4.1823 Y6.7787 -G0 Z0.25 -G0 X2.2839 Y5.9701 -G1 Z-0.05 F30 -G1 X2.2429 Y6.1025 F10 -G3 X2.1238 Y6.1034 I-0.0597 J-0.0185 -G1 X2.0805 Y5.9701 -G1 X1.9403 Y5.9701 -G3 X1.8778 Y5.9076 I0 J-0.0625 -G3 X1.9036 Y5.857 I0.0625 J0 -G1 X2.017 Y5.7747 -G1 X1.9737 Y5.6414 -G3 X1.9706 Y5.6221 I0.0594 J-0.0193 -G3 X2.0699 Y5.5715 I0.0625 J0 -G1 X2.1832 Y5.6539 -G1 X2.2966 Y5.5715 -G3 X2.3958 Y5.6221 I0.0367 J0.0506 -G3 X2.3928 Y5.6414 I-0.0625 J0 -G1 X2.3495 Y5.7747 -G1 X2.4629 Y5.857 -G3 X2.4887 Y5.9076 I-0.0367 J0.0506 -G3 X2.4262 Y5.9701 I-0.0625 J0 -G1 X2.2839 Y5.9701 -G0 Z0.25 -G0 X2.2839 Y5.1616 -G1 Z-0.05 F30 -G1 X2.2429 Y5.294 F10 -G3 X2.1238 Y5.2948 I-0.0597 J-0.0185 -G1 X2.0805 Y5.1616 -G1 X1.9403 Y5.1616 -G3 X1.8778 Y5.0991 I0 J-0.0625 -G3 X1.9036 Y5.0485 I0.0625 J0 -G1 X2.017 Y4.9661 -G1 X1.9737 Y4.8328 -G3 X1.9706 Y4.8135 I0.0594 J-0.0193 -G3 X2.0699 Y4.763 I0.0625 J0 -G1 X2.1832 Y4.8453 -G1 X2.2966 Y4.763 -G3 X2.3958 Y4.8135 I0.0367 J0.0506 -G3 X2.3928 Y4.8328 I-0.0625 J0 -G1 X2.3495 Y4.9661 -G1 X2.4629 Y5.0485 -G3 X2.4887 Y5.0991 I-0.0367 J0.0506 -G3 X2.4262 Y5.1616 I-0.0625 J0 -G1 X2.2839 Y5.1616 -G0 Z0.25 -G0 X4.6569 Y6.3744 -G1 Z-0.05 F30 -G1 X4.616 Y6.5068 F10 -G3 X4.4968 Y6.5076 I-0.0597 J-0.0185 -G1 X4.4535 Y6.3744 -G1 X4.3134 Y6.3744 -G3 X4.2509 Y6.3119 I0 J-0.0625 -G3 X4.2767 Y6.2613 I0.0625 J0 -G1 X4.3901 Y6.1789 -G1 X4.3467 Y6.0457 -G3 X4.3437 Y6.0264 I0.0594 J-0.0193 -G3 X4.4429 Y5.9758 I0.0625 J0 -G1 X4.5563 Y6.0582 -G1 X4.6696 Y5.9758 -G3 X4.7689 Y6.0264 I0.0367 J0.0506 -G3 X4.7658 Y6.0457 I-0.0625 J0 -G1 X4.7225 Y6.1789 -G1 X4.8359 Y6.2613 -G3 X4.8617 Y6.3119 I-0.0367 J0.0506 -G3 X4.7992 Y6.3744 I-0.0625 J0 -G1 X4.6569 Y6.3744 -G0 Z0.25 -G0 X2.2839 Y4.3529 -G1 Z-0.05 F30 -G1 X2.2429 Y4.4853 F10 -G3 X2.1238 Y4.4862 I-0.0597 J-0.0185 -G1 X2.0805 Y4.3529 -G1 X1.9403 Y4.3529 -G3 X1.8778 Y4.2904 I0 J-0.0625 -G3 X1.9036 Y4.2399 I0.0625 J0 -G1 X2.017 Y4.1575 -G1 X1.9737 Y4.0242 -G3 X1.9706 Y4.0049 I0.0594 J-0.0193 -G3 X2.0699 Y3.9543 I0.0625 J0 -G1 X2.1832 Y4.0367 -G1 X2.2966 Y3.9543 -G3 X2.3958 Y4.0049 I0.0367 J0.0506 -G3 X2.3928 Y4.0242 I-0.0625 J0 -G1 X2.3495 Y4.1575 -G1 X2.4629 Y4.2399 -G3 X2.4887 Y4.2904 I-0.0367 J0.0506 -G3 X2.4262 Y4.3529 I-0.0625 J0 -G1 X2.2839 Y4.3529 -G0 Z0.25 -G0 X2.7585 Y4.7572 -G1 Z-0.05 F30 -G1 X2.7175 Y4.8896 F10 -G3 X2.5984 Y4.8904 I-0.0597 J-0.0185 -G1 X2.5551 Y4.7572 -G1 X2.415 Y4.7572 -G3 X2.3525 Y4.6947 I0 J-0.0625 -G3 X2.3783 Y4.6441 I0.0625 J0 -G1 X2.4916 Y4.5618 -G1 X2.4483 Y4.4285 -G3 X2.4452 Y4.4092 I0.0594 J-0.0193 -G3 X2.5445 Y4.3586 I0.0625 J0 -G1 X2.6578 Y4.441 -G1 X2.7712 Y4.3586 -G3 X2.8704 Y4.4092 I0.0367 J0.0506 -G3 X2.8674 Y4.4285 I-0.0625 J0 -G1 X2.8241 Y4.5617 -G1 X2.9375 Y4.6441 -G3 X2.9632 Y4.6947 I-0.0367 J0.0506 -G3 X2.9007 Y4.7572 I-0.0625 J0 -G1 X2.7585 Y4.7572 -G0 Z0.25 -G0 X1.3346 Y5.1616 -G1 Z-0.05 F30 -G1 X1.2937 Y5.294 F10 -G3 X1.1745 Y5.2948 I-0.0597 J-0.0185 -G1 X1.1313 Y5.1616 -G1 X0.9912 Y5.1616 -G3 X0.9287 Y5.0991 I0 J-0.0625 -G3 X0.9544 Y5.0485 I0.0625 J0 -G1 X1.0678 Y4.9661 -G1 X1.0244 Y4.8329 -G3 X1.0214 Y4.8135 I0.0594 J-0.0193 -G3 X1.1206 Y4.763 I0.0625 J0 -G1 X1.234 Y4.8454 -G1 X1.3475 Y4.763 -G3 X1.4467 Y4.8135 I0.0367 J0.0506 -G3 X1.4436 Y4.8329 I-0.0625 J0 -G1 X1.4003 Y4.9661 -G1 X1.5136 Y5.0485 -G3 X1.5394 Y5.0991 I-0.0367 J0.0506 -G3 X1.4769 Y5.1616 I-0.0625 J0 -G1 X1.3346 Y5.1616 -G0 Z0.25 -G0 X0.8601 Y6.3744 -G1 Z-0.05 F30 -G1 X0.8191 Y6.5068 F10 -G3 X0.6999 Y6.5076 I-0.0597 J-0.0185 -G1 X0.6567 Y6.3744 -G1 X0.5166 Y6.3744 -G3 X0.4541 Y6.3119 I0 J-0.0625 -G3 X0.4798 Y6.2613 I0.0625 J0 -G1 X0.5932 Y6.1789 -G1 X0.5498 Y6.0457 -G3 X0.5468 Y6.0264 I0.0594 J-0.0193 -G3 X0.646 Y5.9758 I0.0625 J0 -G1 X0.7594 Y6.0582 -G1 X0.8727 Y5.9758 -G3 X0.972 Y6.0264 I0.0367 J0.0506 -G3 X0.9689 Y6.0457 I-0.0625 J0 -G1 X0.9257 Y6.1789 -G1 X1.039 Y6.2613 -G3 X1.0648 Y6.3119 I-0.0367 J0.0506 -G3 X1.0023 Y6.3744 I-0.0625 J0 -G1 X0.8601 Y6.3744 -G0 Z0.25 -G0 X3.2331 Y4.3529 -G1 Z-0.05 F30 -G1 X3.1921 Y4.4853 F10 -G3 X3.073 Y4.4862 I-0.0597 J-0.0185 -G1 X3.0297 Y4.3529 -G1 X2.8896 Y4.3529 -G3 X2.8271 Y4.2904 I0 J-0.0625 -G3 X2.8529 Y4.2399 I0.0625 J0 -G1 X2.9662 Y4.1575 -G1 X2.9229 Y4.0242 -G3 X2.9198 Y4.0049 I0.0594 J-0.0193 -G3 X3.019 Y3.9543 I0.0625 J0 -G1 X3.1324 Y4.0367 -G1 X3.2459 Y3.9543 -G3 X3.3451 Y4.0049 I0.0367 J0.0506 -G3 X3.342 Y4.0242 I-0.0625 J0 -G1 X3.2987 Y4.1575 -G1 X3.4121 Y4.2399 -G3 X3.4378 Y4.2904 I-0.0367 J0.0506 -G3 X3.3753 Y4.3529 I-0.0625 J0 -G1 X3.2331 Y4.3529 -G0 Z0.25 -G0 X1.3346 Y6.7787 -G1 Z-0.05 F30 -G1 X1.2937 Y6.9112 F10 -G3 X1.1745 Y6.912 I-0.0597 J-0.0185 -G1 X1.1313 Y6.7787 -G1 X0.9912 Y6.7787 -G3 X0.9287 Y6.7162 I0 J-0.0625 -G3 X0.9544 Y6.6657 I0.0625 J0 -G1 X1.0678 Y6.5833 -G1 X1.0244 Y6.4501 -G3 X1.0214 Y6.4307 I0.0594 J-0.0193 -G3 X1.1206 Y6.3802 I0.0625 J0 -G1 X1.234 Y6.4625 -G1 X1.3475 Y6.3802 -G3 X1.4467 Y6.4307 I0.0367 J0.0506 -G3 X1.4436 Y6.4501 I-0.0625 J0 -G1 X1.4003 Y6.5833 -G1 X1.5136 Y6.6657 -G3 X1.5394 Y6.7162 I-0.0367 J0.0506 -G3 X1.4769 Y6.7787 I-0.0625 J0 -G1 X1.3346 Y6.7787 -G0 Z0.25 -G0 X0.8601 Y4.7572 -G1 Z-0.05 F30 -G1 X0.8191 Y4.8896 F10 -G3 X0.6999 Y4.8904 I-0.0597 J-0.0185 -G1 X0.6567 Y4.7572 -G1 X0.5166 Y4.7572 -G3 X0.4541 Y4.6947 I0 J-0.0625 -G3 X0.4798 Y4.6441 I0.0625 J0 -G1 X0.5932 Y4.5618 -G1 X0.5498 Y4.4285 -G3 X0.5468 Y4.4092 I0.0594 J-0.0193 -G3 X0.646 Y4.3586 I0.0625 J0 -G1 X0.7594 Y4.441 -G1 X0.8727 Y4.3586 -G3 X0.972 Y4.4092 I0.0367 J0.0506 -G3 X0.9689 Y4.4285 I-0.0625 J0 -G1 X0.9257 Y4.5617 -G1 X1.039 Y4.6441 -G3 X1.0648 Y4.6947 I-0.0367 J0.0506 -G3 X1.0023 Y4.7572 I-0.0625 J0 -G1 X0.8601 Y4.7572 -G0 Z0.25 -G0 X2.2839 Y6.7787 -G1 Z-0.05 F30 -G1 X2.2429 Y6.9112 F10 -G3 X2.1238 Y6.912 I-0.0597 J-0.0185 -G1 X2.0805 Y6.7787 -G1 X1.9403 Y6.7787 -G3 X1.8778 Y6.7162 I0 J-0.0625 -G3 X1.9036 Y6.6657 I0.0625 J0 -G1 X2.017 Y6.5833 -G1 X1.9737 Y6.45 -G3 X1.9706 Y6.4307 I0.0594 J-0.0193 -G3 X2.0699 Y6.3802 I0.0625 J0 -G1 X2.1832 Y6.4625 -G1 X2.2966 Y6.3802 -G3 X2.3958 Y6.4307 I0.0367 J0.0506 -G3 X2.3928 Y6.45 I-0.0625 J0 -G1 X2.3495 Y6.5833 -G1 X2.4629 Y6.6657 -G3 X2.4887 Y6.7162 I-0.0367 J0.0506 -G3 X2.4262 Y6.7787 I-0.0625 J0 -G1 X2.2839 Y6.7787 -G0 Z0.25 -G0 X5.1315 Y5.1616 -G1 Z-0.05 F30 -G1 X5.0905 Y5.294 F10 -G3 X4.9714 Y5.2948 I-0.0597 J-0.0185 -G1 X4.9281 Y5.1616 -G1 X4.788 Y5.1616 -G3 X4.7255 Y5.0991 I0 J-0.0625 -G3 X4.7513 Y5.0485 I0.0625 J0 -G1 X4.8646 Y4.9661 -G1 X4.8213 Y4.8329 -G3 X4.8182 Y4.8135 I0.0594 J-0.0193 -G3 X4.9175 Y4.763 I0.0625 J0 -G1 X5.0309 Y4.8454 -G1 X5.1443 Y4.763 -G3 X5.2435 Y4.8135 I0.0367 J0.0506 -G3 X5.2405 Y4.8329 I-0.0625 J0 -G1 X5.1971 Y4.9661 -G1 X5.3105 Y5.0485 -G3 X5.3363 Y5.0991 I-0.0367 J0.0506 -G3 X5.2738 Y5.1616 I-0.0625 J0 -G1 X5.1315 Y5.1616 -G0 Z0.25 -G0 X3.2331 Y5.9701 -G1 Z-0.05 F30 -G1 X3.1921 Y6.1025 F10 -G3 X3.073 Y6.1034 I-0.0597 J-0.0185 -G1 X3.0297 Y5.9701 -G1 X2.8896 Y5.9701 -G3 X2.8271 Y5.9076 I0 J-0.0625 -G3 X2.8529 Y5.857 I0.0625 J0 -G1 X2.9662 Y5.7747 -G1 X2.9229 Y5.6414 -G3 X2.9198 Y5.6221 I0.0594 J-0.0193 -G3 X3.019 Y5.5715 I0.0625 J0 -G1 X3.1324 Y5.6539 -G1 X3.2459 Y5.5715 -G3 X3.3451 Y5.6221 I0.0367 J0.0506 -G3 X3.342 Y5.6414 I-0.0625 J0 -G1 X3.2987 Y5.7747 -G1 X3.4121 Y5.857 -G3 X3.4378 Y5.9076 I-0.0367 J0.0506 -G3 X3.3753 Y5.9701 I-0.0625 J0 -G1 X3.2331 Y5.9701 -G0 Z0.25 -G0 X4.1823 Y5.9701 -G1 Z-0.05 F30 -G1 X4.1414 Y6.1025 F10 -G3 X4.0222 Y6.1034 I-0.0597 J-0.0185 -G1 X3.979 Y5.9701 -G1 X3.8388 Y5.9701 -G3 X3.7763 Y5.9076 I0 J-0.0625 -G3 X3.802 Y5.857 I0.0625 J0 -G1 X3.9154 Y5.7747 -G1 X3.8721 Y5.6414 -G3 X3.8691 Y5.6221 I0.0594 J-0.0193 -G3 X3.9683 Y5.5715 I0.0625 J0 -G1 X4.0817 Y5.6539 -G1 X4.195 Y5.5715 -G3 X4.2943 Y5.6221 I0.0367 J0.0506 -G3 X4.2912 Y5.6414 I-0.0625 J0 -G1 X4.248 Y5.7747 -G1 X4.3613 Y5.857 -G3 X4.3871 Y5.9076 I-0.0367 J0.0506 -G3 X4.3246 Y5.9701 I-0.0625 J0 -G1 X4.1823 Y5.9701 -G0 Z0.25 -G0 X4.1823 Y5.1616 -G1 Z-0.05 F30 -G1 X4.1414 Y5.294 F10 -G3 X4.0222 Y5.2948 I-0.0597 J-0.0185 -G1 X3.979 Y5.1616 -G1 X3.8388 Y5.1616 -G3 X3.7763 Y5.0991 I0 J-0.0625 -G3 X3.802 Y5.0485 I0.0625 J0 -G1 X3.9154 Y4.9661 -G1 X3.8721 Y4.8328 -G3 X3.8691 Y4.8135 I0.0594 J-0.0193 -G3 X3.9683 Y4.763 I0.0625 J0 -G1 X4.0817 Y4.8453 -G1 X4.195 Y4.763 -G3 X4.2943 Y4.8135 I0.0367 J0.0506 -G3 X4.2912 Y4.8328 I-0.0625 J0 -G1 X4.248 Y4.9661 -G1 X4.3613 Y5.0485 -G3 X4.3871 Y5.0991 I-0.0367 J0.0506 -G3 X4.3246 Y5.1616 I-0.0625 J0 -G1 X4.1823 Y5.1616 -G0 Z0.25 -G0 X5.1315 Y6.7787 -G1 Z-0.05 F30 -G1 X5.0905 Y6.9112 F10 -G3 X4.9714 Y6.912 I-0.0597 J-0.0185 -G1 X4.9281 Y6.7787 -G1 X4.788 Y6.7787 -G3 X4.7255 Y6.7162 I0 J-0.0625 -G3 X4.7513 Y6.6657 I0.0625 J0 -G1 X4.8646 Y6.5833 -G1 X4.8213 Y6.4501 -G3 X4.8182 Y6.4307 I0.0594 J-0.0193 -G3 X4.9175 Y6.3802 I0.0625 J0 -G1 X5.0309 Y6.4625 -G1 X5.1443 Y6.3802 -G3 X5.2435 Y6.4307 I0.0367 J0.0506 -G3 X5.2405 Y6.4501 I-0.0625 J0 -G1 X5.1971 Y6.5833 -G1 X5.3105 Y6.6657 -G3 X5.3363 Y6.7162 I-0.0367 J0.0506 -G3 X5.2738 Y6.7787 I-0.0625 J0 -G1 X5.1315 Y6.7787 -G0 Z0.25 -G0 X2.7585 Y5.5667 -G1 Z-0.05 F30 -G1 X2.7175 Y5.6992 F10 -G3 X2.5984 Y5.7 I-0.0597 J-0.0185 -G1 X2.5551 Y5.5667 -G1 X2.415 Y5.5667 -G3 X2.3525 Y5.5042 I0 J-0.0625 -G3 X2.3783 Y5.4536 I0.0625 J0 -G1 X2.4916 Y5.3712 -G1 X2.4483 Y5.238 -G3 X2.4452 Y5.2186 I0.0594 J-0.0193 -G3 X2.5445 Y5.1681 I0.0625 J0 -G1 X2.6578 Y5.2505 -G1 X2.7712 Y5.1681 -G3 X2.8704 Y5.2186 I0.0367 J0.0506 -G3 X2.8674 Y5.2379 I-0.0625 J0 -G1 X2.8241 Y5.3712 -G1 X2.9375 Y5.4536 -G3 X2.9632 Y5.5042 I-0.0367 J0.0506 -G3 X2.9007 Y5.5667 I-0.0625 J0 -G1 X2.7585 Y5.5667 -G0 Z0.25 -G0 X4.6569 Y5.5667 -G1 Z-0.05 F30 -G1 X4.616 Y5.6992 F10 -G3 X4.4968 Y5.7 I-0.0597 J-0.0185 -G1 X4.4535 Y5.5667 -G1 X4.3134 Y5.5667 -G3 X4.2509 Y5.5042 I0 J-0.0625 -G3 X4.2767 Y5.4536 I0.0625 J0 -G1 X4.3901 Y5.3712 -G1 X4.3467 Y5.238 -G3 X4.3437 Y5.2186 I0.0594 J-0.0193 -G3 X4.4429 Y5.1681 I0.0625 J0 -G1 X4.5563 Y5.2505 -G1 X4.6696 Y5.1681 -G3 X4.7689 Y5.2186 I0.0367 J0.0506 -G3 X4.7658 Y5.2379 I-0.0625 J0 -G1 X4.7225 Y5.3712 -G1 X4.8359 Y5.4536 -G3 X4.8617 Y5.5042 I-0.0367 J0.0506 -G3 X4.7992 Y5.5667 I-0.0625 J0 -G1 X4.6569 Y5.5667 -G0 Z0.25 -G0 X0.8601 Y5.5667 -G1 Z-0.05 F30 -G1 X0.8191 Y5.6992 F10 -G3 X0.6999 Y5.7 I-0.0597 J-0.0185 -G1 X0.6567 Y5.5667 -G1 X0.5166 Y5.5667 -G3 X0.4541 Y5.5042 I0 J-0.0625 -G3 X0.4798 Y5.4536 I0.0625 J0 -G1 X0.5932 Y5.3712 -G1 X0.5498 Y5.238 -G3 X0.5468 Y5.2186 I0.0594 J-0.0193 -G3 X0.646 Y5.1681 I0.0625 J0 -G1 X0.7594 Y5.2505 -G1 X0.8727 Y5.1681 -G3 X0.972 Y5.2186 I0.0367 J0.0506 -G3 X0.9689 Y5.2379 I-0.0625 J0 -G1 X0.9257 Y5.3712 -G1 X1.039 Y5.4536 -G3 X1.0648 Y5.5042 I-0.0367 J0.0506 -G3 X1.0023 Y5.5667 I-0.0625 J0 -G1 X0.8601 Y5.5667 -G0 Z0.25 -G0 X5.6061 Y4.7572 -G1 Z-0.05 F30 -G1 X5.5652 Y4.8896 F10 -G3 X5.4461 Y4.8905 I-0.0597 J-0.0184 -G1 X5.4027 Y4.7572 -G1 X5.2626 Y4.7572 -G3 X5.2001 Y4.6947 I0 J-0.0625 -G3 X5.2259 Y4.6441 I0.0625 J0 -G1 X5.3393 Y4.5617 -G1 X5.296 Y4.4285 -G3 X5.2929 Y4.4092 I0.0594 J-0.0193 -G3 X5.3922 Y4.3586 I0.0625 J0 -G1 X5.5055 Y4.441 -G1 X5.6189 Y4.3586 -G3 X5.7181 Y4.4092 I0.0367 J0.0506 -G3 X5.7151 Y4.4285 I-0.0625 J0 -G1 X5.6717 Y4.5618 -G1 X5.7851 Y4.6441 -G3 X5.8108 Y4.6947 I-0.0367 J0.0506 -G3 X5.7483 Y4.7572 I-0.0625 J0 -G1 X5.6061 Y4.7572 -G0 Z0.25 -G0 X1.3347 Y5.9701 -G1 Z-0.05 F30 -G1 X1.2938 Y6.1025 F10 -G3 X1.1746 Y6.1034 I-0.0597 J-0.0184 -G1 X1.1313 Y5.9701 -G1 X0.9912 Y5.9701 -G3 X0.9287 Y5.9076 I0 J-0.0625 -G3 X0.9544 Y5.857 I0.0625 J0 -G1 X1.0678 Y5.7747 -G1 X1.0244 Y5.6414 -G3 X1.0214 Y5.6221 I0.0594 J-0.0193 -G3 X1.1206 Y5.5715 I0.0625 J0 -G1 X1.2341 Y5.6539 -G1 X1.3474 Y5.5715 -G3 X1.4467 Y5.6221 I0.0367 J0.0506 -G3 X1.4436 Y5.6414 I-0.0625 J0 -G1 X1.4003 Y5.7747 -G1 X1.5136 Y5.857 -G3 X1.5394 Y5.9076 I-0.0367 J0.0506 -G3 X1.4769 Y5.9701 I-0.0625 J0 -G1 X1.3347 Y5.9701 -G0 Z0.25 -G0 X3.7077 Y4.7572 -G1 Z-0.05 F30 -G1 X3.6668 Y4.8896 F10 -G3 X3.5477 Y4.8905 I-0.0597 J-0.0184 -G1 X3.5043 Y4.7572 -G1 X3.3642 Y4.7572 -G3 X3.3017 Y4.6947 I0 J-0.0625 -G3 X3.3274 Y4.6441 I0.0625 J0 -G1 X3.4408 Y4.5617 -G1 X3.3975 Y4.4285 -G3 X3.3945 Y4.4092 I0.0594 J-0.0193 -G3 X3.4937 Y4.3586 I0.0625 J0 -G1 X3.6071 Y4.441 -G1 X3.7205 Y4.3586 -G3 X3.8197 Y4.4092 I0.0367 J0.0506 -G3 X3.8166 Y4.4285 I-0.0625 J0 -G1 X3.7733 Y4.5618 -G1 X3.8866 Y4.6441 -G3 X3.9124 Y4.6947 I-0.0367 J0.0506 -G3 X3.8499 Y4.7572 I-0.0625 J0 -G1 X3.7077 Y4.7572 -G0 Z0.25 -G0 X1.3347 Y4.3529 -G1 Z-0.05 F30 -G1 X1.2938 Y4.4853 F10 -G3 X1.1746 Y4.4862 I-0.0597 J-0.0184 -G1 X1.1313 Y4.3529 -G1 X0.9912 Y4.3529 -G3 X0.9287 Y4.2904 I0 J-0.0625 -G3 X0.9544 Y4.2399 I0.0625 J0 -G1 X1.0678 Y4.1575 -G1 X1.0244 Y4.0242 -G3 X1.0214 Y4.0049 I0.0594 J-0.0193 -G3 X1.1206 Y3.9543 I0.0625 J0 -G1 X1.2341 Y4.0367 -G1 X1.3474 Y3.9543 -G3 X1.4467 Y4.0049 I0.0367 J0.0506 -G3 X1.4436 Y4.0242 I-0.0625 J0 -G1 X1.4003 Y4.1575 -G1 X1.5136 Y4.2399 -G3 X1.5394 Y4.2904 I-0.0367 J0.0506 -G3 X1.4769 Y4.3529 I-0.0625 J0 -G1 X1.3347 Y4.3529 -G0 Z0.25 -G0 X3.7077 Y6.3744 -G1 Z-0.05 F30 -G1 X3.6668 Y6.5068 F10 -G3 X3.5477 Y6.5077 I-0.0597 J-0.0184 -G1 X3.5043 Y6.3744 -G1 X3.3642 Y6.3744 -G3 X3.3017 Y6.3119 I0 J-0.0625 -G3 X3.3274 Y6.2613 I0.0625 J0 -G1 X3.4408 Y6.1789 -G1 X3.3975 Y6.0457 -G3 X3.3945 Y6.0264 I0.0594 J-0.0193 -G3 X3.4937 Y5.9758 I0.0625 J0 -G1 X3.6071 Y6.0582 -G1 X3.7205 Y5.9758 -G3 X3.8197 Y6.0264 I0.0367 J0.0506 -G3 X3.8166 Y6.0457 I-0.0625 J0 -G1 X3.7733 Y6.1789 -G1 X3.8866 Y6.2613 -G3 X3.9124 Y6.3119 I-0.0367 J0.0506 -G3 X3.8499 Y6.3744 I-0.0625 J0 -G1 X3.7077 Y6.3744 -G0 Z0.25 -G0 X1.8092 Y4.7572 -G1 Z-0.05 F30 -G1 X1.7684 Y4.8896 F10 -G3 X1.6492 Y4.8905 I-0.0597 J-0.0184 -G1 X1.6059 Y4.7572 -G1 X1.4657 Y4.7572 -G3 X1.4032 Y4.6947 I0 J-0.0625 -G3 X1.429 Y4.6441 I0.0625 J0 -G1 X1.5424 Y4.5617 -G1 X1.4991 Y4.4285 -G3 X1.496 Y4.4092 I0.0594 J-0.0193 -G3 X1.5953 Y4.3586 I0.0625 J0 -G1 X1.7087 Y4.441 -G1 X1.822 Y4.3586 -G3 X1.9213 Y4.4092 I0.0367 J0.0506 -G3 X1.9182 Y4.4285 I-0.0625 J0 -G1 X1.8748 Y4.5618 -G1 X1.9882 Y4.6441 -G3 X2.014 Y4.6947 I-0.0367 J0.0506 -G3 X1.9515 Y4.7572 I-0.0625 J0 -G1 X1.8092 Y4.7572 -G0 Z0.25 -G0 X1.8092 Y6.3744 -G1 Z-0.05 F30 -G1 X1.7684 Y6.5068 F10 -G3 X1.6492 Y6.5077 I-0.0597 J-0.0184 -G1 X1.6059 Y6.3744 -G1 X1.4657 Y6.3744 -G3 X1.4032 Y6.3119 I0 J-0.0625 -G3 X1.429 Y6.2613 I0.0625 J0 -G1 X1.5424 Y6.1789 -G1 X1.4991 Y6.0457 -G3 X1.496 Y6.0264 I0.0594 J-0.0193 -G3 X1.5953 Y5.9758 I0.0625 J0 -G1 X1.7087 Y6.0582 -G1 X1.822 Y5.9758 -G3 X1.9213 Y6.0264 I0.0367 J0.0506 -G3 X1.9182 Y6.0457 I-0.0625 J0 -G1 X1.8748 Y6.1789 -G1 X1.9882 Y6.2613 -G3 X2.014 Y6.3119 I-0.0367 J0.0506 -G3 X1.9515 Y6.3744 I-0.0625 J0 -G1 X1.8092 Y6.3744 -G0 Z0.25 -G0 X5.6061 Y6.3744 -G1 Z-0.05 F30 -G1 X5.5652 Y6.5068 F10 -G3 X5.4461 Y6.5077 I-0.0597 J-0.0184 -G1 X5.4027 Y6.3744 -G1 X5.2626 Y6.3744 -G3 X5.2001 Y6.3119 I0 J-0.0625 -G3 X5.2259 Y6.2613 I0.0625 J0 -G1 X5.3393 Y6.1789 -G1 X5.296 Y6.0457 -G3 X5.2929 Y6.0264 I0.0594 J-0.0193 -G3 X5.3922 Y5.9758 I0.0625 J0 -G1 X5.5055 Y6.0582 -G1 X5.6189 Y5.9758 -G3 X5.7181 Y6.0264 I0.0367 J0.0506 -G3 X5.7151 Y6.0457 I-0.0625 J0 -G1 X5.6717 Y6.1789 -G1 X5.7851 Y6.2613 -G3 X5.8108 Y6.3119 I-0.0367 J0.0506 -G3 X5.7483 Y6.3744 I-0.0625 J0 -G1 X5.6061 Y6.3744 -G0 Z0.25 -G0 X1.8093 Y5.5667 -G1 Z-0.05 F30 -G1 X1.7684 Y5.6992 F10 -G3 X1.6492 Y5.7001 I-0.0597 J-0.0184 -G1 X1.6059 Y5.5667 -G1 X1.4657 Y5.5667 -G3 X1.4032 Y5.5042 I0 J-0.0625 -G3 X1.429 Y5.4536 I0.0625 J0 -G1 X1.5424 Y5.3712 -G1 X1.4991 Y5.2379 -G3 X1.496 Y5.2186 I0.0594 J-0.0193 -G3 X1.5953 Y5.1681 I0.0625 J0 -G1 X1.7087 Y5.2505 -G1 X1.822 Y5.1681 -G3 X1.9213 Y5.2186 I0.0367 J0.0506 -G3 X1.9182 Y5.238 I-0.0625 J0 -G1 X1.8748 Y5.3712 -G1 X1.9882 Y5.4536 -G3 X2.014 Y5.5042 I-0.0367 J0.0506 -G3 X1.9515 Y5.5667 I-0.0625 J0 -G1 X1.8093 Y5.5667 -G0 Z0.25 -G0 X3.7077 Y5.5667 -G1 Z-0.05 F30 -G1 X3.6668 Y5.6992 F10 -G3 X3.5477 Y5.7001 I-0.0597 J-0.0184 -G1 X3.5043 Y5.5667 -G1 X3.3642 Y5.5667 -G3 X3.3017 Y5.5042 I0 J-0.0625 -G3 X3.3274 Y5.4536 I0.0625 J0 -G1 X3.4408 Y5.3712 -G1 X3.3975 Y5.2379 -G3 X3.3945 Y5.2186 I0.0594 J-0.0193 -G3 X3.4937 Y5.1681 I0.0625 J0 -G1 X3.6071 Y5.2505 -G1 X3.7205 Y5.1681 -G3 X3.8197 Y5.2186 I0.0367 J0.0506 -G3 X3.8166 Y5.238 I-0.0625 J0 -G1 X3.7733 Y5.3712 -G1 X3.8866 Y5.4536 -G3 X3.9124 Y5.5042 I-0.0367 J0.0506 -G3 X3.8499 Y5.5667 I-0.0625 J0 -G1 X3.7077 Y5.5667 -G0 Z0.25 -G0 X5.6061 Y5.5667 -G1 Z-0.05 F30 -G1 X5.5652 Y5.6992 F10 -G3 X5.4461 Y5.7001 I-0.0597 J-0.0184 -G1 X5.4027 Y5.5667 -G1 X5.2626 Y5.5667 -G3 X5.2001 Y5.5042 I0 J-0.0625 -G3 X5.2259 Y5.4536 I0.0625 J0 -G1 X5.3393 Y5.3712 -G1 X5.296 Y5.2379 -G3 X5.2929 Y5.2186 I0.0594 J-0.0193 -G3 X5.3922 Y5.1681 I0.0625 J0 -G1 X5.5055 Y5.2505 -G1 X5.6189 Y5.1681 -G3 X5.7181 Y5.2186 I0.0367 J0.0506 -G3 X5.7151 Y5.238 I-0.0625 J0 -G1 X5.6717 Y5.3712 -G1 X5.7851 Y5.4536 -G3 X5.8108 Y5.5042 I-0.0367 J0.0506 -G3 X5.7483 Y5.5667 I-0.0625 J0 -G1 X5.6061 Y5.5667 -G0 Z0.25 -G0 X3.1567 Y7.1674 -G1 Z-0.05 F30 -G1 X3.1082 Y7.1674 F10 -G2 X3.1132 Y7.1214 I-0.2075 J-0.046 -G2 X3.1125 Y7.1043 I-0.2125 J0 -G2 X3.1524 Y7.1043 I0.0199 J-0.2116 -G2 X3.1517 Y7.1214 I0.2118 J0.0171 -G2 X3.1567 Y7.1674 I0.2125 J0 -G1 X3.2017 Y7.1214 F10 -G2 X3.2331 Y7.2174 I0.1625 J0 F10 -G1 X3.0318 Y7.2174 -G2 X3.0632 Y7.1214 I-0.1311 J-0.096 -G2 X2.9963 Y6.9899 I-0.1625 J0 -G1 X2.9416 Y6.9502 -G1 X2.9609 Y6.8908 -G1 X2.9778 Y6.9429 -G2 X3.2876 Y6.9407 I0.1546 J-0.0502 -G1 X3.3035 Y6.8894 -G1 X3.3233 Y6.9502 -G1 X3.2687 Y6.9899 -G2 X3.2017 Y7.1214 I0.0955 J0.1315 -G1 X3.2517 Y7.1214 F10 -G2 X3.3642 Y7.2339 I0.1125 J0 F10 -G1 X3.468 Y7.2339 -G1 X3.4789 Y7.2674 -G1 X2.785 Y7.2674 -G1 X2.7954 Y7.2339 -G1 X2.9007 Y7.2339 -G2 X3.0132 Y7.1214 I0 J-0.1125 -G2 X2.9669 Y7.0303 I-0.1125 J0 -G1 X2.8829 Y6.9693 -G1 X2.9149 Y6.8706 -G2 X2.9204 Y6.8358 I-0.107 J-0.0347 -G2 X2.9202 Y6.8287 I-0.1125 J0 -G1 X2.9934 Y6.8287 -G1 X3.0254 Y6.9274 -G2 X3.2399 Y6.926 I0.107 J-0.0347 -G1 X3.2699 Y6.8287 -G1 X3.3447 Y6.8287 -G2 X3.3445 Y6.8358 I0.1123 J0.0071 -G2 X3.35 Y6.8706 I0.1125 J0 -G1 X3.382 Y6.9693 -G1 X3.298 Y7.0303 -G2 X3.2517 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X5.0552 Y7.1674 -G1 Z-0.05 F30 -G1 X5.0066 Y7.1674 F10 -G2 X5.0117 Y7.1214 I-0.2075 J-0.046 -G2 X5.011 Y7.1043 I-0.2125 J0 -G2 X5.0508 Y7.1043 I0.0199 J-0.2116 -G2 X5.0501 Y7.1214 I0.2118 J0.0171 -G2 X5.0552 Y7.1674 I0.2125 J0 -G1 X5.1001 Y7.1214 F10 -G2 X5.1315 Y7.2174 I0.1625 J0 F10 -G1 X4.9303 Y7.2174 -G2 X4.9617 Y7.1214 I-0.1311 J-0.096 -G2 X4.8947 Y6.9899 I-0.1625 J0 -G1 X4.8401 Y6.9502 -G1 X4.8594 Y6.8908 -G1 X4.8763 Y6.9429 -G2 X5.1861 Y6.9407 I0.1546 J-0.0502 -G1 X5.202 Y6.8894 -G1 X5.2217 Y6.9502 -G1 X5.1671 Y6.9899 -G2 X5.1001 Y7.1214 I0.0955 J0.1315 -G1 X5.1501 Y7.1214 F10 -G2 X5.2626 Y7.2339 I0.1125 J0 F10 -G1 X5.3664 Y7.2339 -G1 X5.3773 Y7.2674 -G1 X4.6834 Y7.2674 -G1 X4.6938 Y7.2339 -G1 X4.7992 Y7.2339 -G2 X4.9117 Y7.1214 I0 J-0.1125 -G2 X4.8653 Y7.0303 I-0.1125 J0 -G1 X4.7813 Y6.9693 -G1 X4.8134 Y6.8706 -G2 X4.8189 Y6.8358 I-0.107 J-0.0347 -G2 X4.8186 Y6.8287 I-0.1125 J0 -G1 X4.8918 Y6.8287 -G1 X4.9238 Y6.9274 -G2 X5.1383 Y6.926 I0.107 J-0.0347 -G1 X5.1684 Y6.8287 -G1 X5.2431 Y6.8287 -G2 X5.2429 Y6.8358 I0.1123 J0.0071 -G2 X5.2484 Y6.8706 I0.1125 J0 -G1 X5.2805 Y6.9693 -G1 X5.1965 Y7.0303 -G2 X5.1501 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X1.2583 Y7.1674 -G1 Z-0.05 F30 -G1 X1.2098 Y7.1674 F10 -G2 X1.2148 Y7.1214 I-0.2075 J-0.046 -G2 X1.2141 Y7.1043 I-0.2125 J0 -G2 X1.2539 Y7.1043 I0.0199 J-0.2116 -G2 X1.2532 Y7.1214 I0.2118 J0.0171 -G2 X1.2583 Y7.1674 I0.2125 J0 -G1 X1.3032 Y7.1214 F10 -G2 X1.3347 Y7.2174 I0.1625 J0 F10 -G1 X1.1334 Y7.2174 -G2 X1.1648 Y7.1214 I-0.1311 J-0.096 -G2 X1.0978 Y6.9899 I-0.1625 J0 -G1 X1.0432 Y6.9502 -G1 X1.0625 Y6.8908 -G1 X1.0794 Y6.9429 -G2 X1.3892 Y6.9407 I0.1546 J-0.0502 -G1 X1.4051 Y6.8894 -G1 X1.4248 Y6.9502 -G1 X1.3702 Y6.9899 -G2 X1.3032 Y7.1214 I0.0955 J0.1315 -G1 X1.3532 Y7.1214 F10 -G2 X1.4657 Y7.2339 I0.1125 J0 F10 -G1 X1.5695 Y7.2339 -G1 X1.5804 Y7.2674 -G1 X0.8866 Y7.2674 -G1 X0.8969 Y7.2339 -G1 X1.0023 Y7.2339 -G2 X1.1148 Y7.1214 I0 J-0.1125 -G2 X1.0684 Y7.0303 I-0.1125 J0 -G1 X0.9844 Y6.9693 -G1 X1.0165 Y6.8706 -G2 X1.022 Y6.8358 I-0.107 J-0.0347 -G2 X1.0218 Y6.8287 I-0.1125 J0 -G1 X1.0949 Y6.8287 -G1 X1.127 Y6.9274 -G2 X1.3414 Y6.926 I0.107 J-0.0347 -G1 X1.3715 Y6.8287 -G1 X1.4463 Y6.8287 -G2 X1.446 Y6.8358 I0.1123 J0.0071 -G2 X1.4515 Y6.8706 I0.1125 J0 -G1 X1.4836 Y6.9693 -G1 X1.3996 Y7.0303 -G2 X1.3532 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X2.2076 Y7.1674 -G1 Z-0.05 F30 -G1 X2.1589 Y7.1674 F10 -G2 X2.164 Y7.1214 I-0.2075 J-0.046 -G2 X2.1633 Y7.1043 I-0.2125 J0 -G2 X2.2032 Y7.1043 I0.02 J-0.2116 -G2 X2.2025 Y7.1214 I0.2118 J0.0171 -G2 X2.2076 Y7.1674 I0.2125 J0 -G1 X2.2525 Y7.1214 F10 -G2 X2.2839 Y7.2174 I0.1625 J0 F10 -G1 X2.0825 Y7.2174 -G2 X2.114 Y7.1214 I-0.1311 J-0.096 -G2 X2.047 Y6.9899 I-0.1625 J0 -G1 X1.9924 Y6.9502 -G1 X2.0118 Y6.8908 -G1 X2.0287 Y6.9429 -G2 X2.3385 Y6.9407 I0.1546 J-0.0502 -G1 X2.3543 Y6.8896 -G1 X2.3741 Y6.9502 -G1 X2.3195 Y6.9899 -G2 X2.2525 Y7.1214 I0.0955 J0.1315 -G1 X2.3025 Y7.1214 F10 -G2 X2.415 Y7.2339 I0.1125 J0 F10 -G1 X2.5188 Y7.2339 -G1 X2.5296 Y7.2674 -G1 X1.8358 Y7.2674 -G1 X1.8462 Y7.2339 -G1 X1.9515 Y7.2339 -G2 X2.064 Y7.1214 I0 J-0.1125 -G2 X2.0176 Y7.0303 I-0.1125 J0 -G1 X1.9336 Y6.9693 -G1 X1.9657 Y6.8706 -G2 X1.9713 Y6.8358 I-0.107 J-0.0348 -G2 X1.971 Y6.8287 I-0.1125 J0 -G1 X2.0442 Y6.8287 -G1 X2.0762 Y6.9274 -G2 X2.2907 Y6.926 I0.107 J-0.0347 -G1 X2.3208 Y6.8287 -G1 X2.3954 Y6.8287 -G2 X2.3952 Y6.8358 I0.1123 J0.0071 -G2 X2.4007 Y6.8706 I0.1125 J0 -G1 X2.4328 Y6.9693 -G1 X2.3489 Y7.0303 -G2 X2.3025 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X4.106 Y7.1674 -G1 Z-0.05 F30 -G1 X4.0574 Y7.1674 F10 -G2 X4.0624 Y7.1214 I-0.2075 J-0.046 -G2 X4.0617 Y7.1043 I-0.2125 J0 -G2 X4.1016 Y7.1043 I0.02 J-0.2116 -G2 X4.1009 Y7.1214 I0.2118 J0.0171 -G2 X4.106 Y7.1674 I0.2125 J0 -G1 X4.1509 Y7.1214 F10 -G2 X4.1824 Y7.2174 I0.1625 J0 F10 -G1 X3.981 Y7.2174 -G2 X4.0124 Y7.1214 I-0.1311 J-0.096 -G2 X3.9454 Y6.9899 I-0.1625 J0 -G1 X3.8909 Y6.9502 -G1 X3.9102 Y6.8908 -G1 X3.9271 Y6.9429 -G2 X4.2369 Y6.9407 I0.1546 J-0.0502 -G1 X4.2527 Y6.8896 -G1 X4.2725 Y6.9502 -G1 X4.2179 Y6.9899 -G2 X4.1509 Y7.1214 I0.0955 J0.1315 -G1 X4.2009 Y7.1214 F10 -G2 X4.3134 Y7.2339 I0.1125 J0 F10 -G1 X4.4172 Y7.2339 -G1 X4.4281 Y7.2674 -G1 X3.7342 Y7.2674 -G1 X3.7446 Y7.2339 -G1 X3.8499 Y7.2339 -G2 X3.9624 Y7.1214 I0 J-0.1125 -G2 X3.916 Y7.0303 I-0.1125 J0 -G1 X3.8321 Y6.9693 -G1 X3.8642 Y6.8706 -G2 X3.8697 Y6.8358 I-0.107 J-0.0348 -G2 X3.8695 Y6.8287 I-0.1125 J0 -G1 X3.9426 Y6.8287 -G1 X3.9747 Y6.9274 -G2 X4.1891 Y6.926 I0.107 J-0.0347 -G1 X4.2192 Y6.8287 -G1 X4.2939 Y6.8287 -G2 X4.2937 Y6.8358 I0.1123 J0.0071 -G2 X4.2992 Y6.8706 I0.1125 J0 -G1 X4.3313 Y6.9693 -G1 X4.2473 Y7.0303 -G2 X4.2009 Y7.1214 I0.0661 J0.091 -G0 Z0.25 -G0 X0.6048 Y6.5385 -G1 Z-0.05 F30 -G2 X0.9146 Y6.5364 I0.1546 J-0.0502 F10 -G1 X0.9306 Y6.4848 -G1 X0.9502 Y6.5451 -G1 X0.8956 Y6.5848 -G2 X0.8302 Y6.694 I0.0955 J0.1315 -G2 X0.814 Y6.7044 I0.0793 J0.1418 -G1 X0.7594 Y6.744 -G1 X0.7048 Y6.7044 -G2 X0.541 Y6.6884 I-0.0955 J0.1315 -G1 X0.541 Y6.4744 -G1 X0.584 Y6.4744 -G1 X0.6048 Y6.5385 -G1 X0.6524 Y6.5231 F10 -G2 X0.8669 Y6.5216 I0.107 J-0.0347 F10 -G1 X0.8969 Y6.4244 -G1 X0.9715 Y6.4244 -G2 X0.9714 Y6.4307 I0.1123 J0.0064 -G2 X0.9769 Y6.4655 I0.1125 J0 -G1 X1.009 Y6.5642 -G1 X0.925 Y6.6252 -G2 X0.8787 Y6.7162 I0.0661 J0.091 -G2 X0.8792 Y6.7275 I0.1125 J0 -G2 X0.8434 Y6.7448 I0.0303 J0.1084 -G1 X0.7594 Y6.8058 -G1 X0.6754 Y6.7448 -G2 X0.4968 Y6.8358 I-0.0661 J0.091 -G2 X0.5023 Y6.8706 I0.1125 J0 -G1 X0.5344 Y6.9693 -G1 X0.491 Y7.0008 -G1 X0.491 Y6.4214 -G2 X0.5166 Y6.4244 I0.0255 J-0.1096 -G1 X0.6203 Y6.4244 -G1 X0.6524 Y6.5231 -G0 Z0.25 -G0 X0.6048 Y4.9213 -G1 Z-0.05 F30 -G2 X0.9146 Y4.9192 I0.1546 J-0.0502 F10 -G1 X0.9306 Y4.8676 -G1 X0.9502 Y4.928 -G1 X0.8956 Y4.9676 -G2 X0.8302 Y5.0768 I0.0955 J0.1315 -G2 X0.814 Y5.0872 I0.0793 J0.1418 -G1 X0.7594 Y5.1268 -G1 X0.7048 Y5.0872 -G2 X0.541 Y5.0712 I-0.0955 J0.1315 -G1 X0.541 Y4.8572 -G1 X0.584 Y4.8572 -G1 X0.6048 Y4.9213 -G1 X0.6524 Y4.9059 F10 -G2 X0.8669 Y4.9044 I0.107 J-0.0347 F10 -G1 X0.8969 Y4.8072 -G1 X0.9715 Y4.8072 -G2 X0.9714 Y4.8135 I0.1123 J0.0064 -G2 X0.9769 Y4.8483 I0.1125 J0 -G1 X1.009 Y4.947 -G1 X0.925 Y5.008 -G2 X0.8787 Y5.0991 I0.0661 J0.091 -G2 X0.8792 Y5.1103 I0.1125 J0 -G2 X0.8434 Y5.1276 I0.0303 J0.1084 -G1 X0.7594 Y5.1886 -G1 X0.6754 Y5.1276 -G2 X0.4968 Y5.2186 I-0.0661 J0.091 -G2 X0.5023 Y5.2534 I0.1125 J0 -G1 X0.5344 Y5.3521 -G1 X0.491 Y5.3836 -G1 X0.491 Y4.8043 -G2 X0.5166 Y4.8072 I0.0255 J-0.1096 -G1 X0.6203 Y4.8072 -G1 X0.6524 Y4.9059 -G0 Z0.25 -G0 X5.351 Y4.9214 -G1 Z-0.05 F30 -G2 X5.6608 Y4.9191 I0.1545 J-0.0503 F10 -G1 X5.6799 Y4.8572 -G1 X5.7239 Y4.8572 -G1 X5.7239 Y5.0712 -G2 X5.5601 Y5.0872 I-0.0682 J0.1475 -G1 X5.5055 Y5.1268 -G1 X5.4509 Y5.0872 -G2 X5.4347 Y5.0768 I-0.0955 J0.1315 -G2 X5.3693 Y4.9676 I-0.161 J0.0223 -G1 X5.3147 Y4.928 -G1 X5.3339 Y4.8689 -G1 X5.351 Y4.9214 -G1 X5.3985 Y4.9059 F10 -G2 X5.613 Y4.9043 I0.107 J-0.0348 F10 -G1 X5.643 Y4.8072 -G1 X5.7483 Y4.8072 -G2 X5.7739 Y4.8043 I0 J-0.1125 -G1 X5.7739 Y5.3836 -G1 X5.7305 Y5.3521 -G1 X5.7626 Y5.2534 -G2 X5.7681 Y5.2186 I-0.107 J-0.0348 -G2 X5.5895 Y5.1276 I-0.1125 J0 -G1 X5.5055 Y5.1886 -G1 X5.4216 Y5.1276 -G2 X5.3857 Y5.1103 I-0.0661 J0.091 -G2 X5.3863 Y5.0991 I-0.1119 J-0.0112 -G2 X5.3399 Y5.008 I-0.1125 J0 -G1 X5.2559 Y4.947 -G1 X5.288 Y4.8483 -G2 X5.2935 Y4.8135 I-0.107 J-0.0348 -G2 X5.2934 Y4.8072 I-0.1125 J0 -G1 X5.3664 Y4.8072 -G1 X5.3985 Y4.9059 -G0 Z0.25 -G0 X5.351 Y6.5386 -G1 Z-0.05 F30 -G2 X5.6608 Y6.5363 I0.1545 J-0.0503 F10 -G1 X5.6799 Y6.4744 -G1 X5.7239 Y6.4744 -G1 X5.7239 Y6.6884 -G2 X5.5601 Y6.7044 I-0.0682 J0.1475 -G1 X5.5055 Y6.744 -G1 X5.4509 Y6.7044 -G2 X5.4347 Y6.694 I-0.0955 J0.1315 -G2 X5.3693 Y6.5848 I-0.161 J0.0223 -G1 X5.3147 Y6.5451 -G1 X5.3339 Y6.4861 -G1 X5.351 Y6.5386 -G1 X5.3985 Y6.5231 F10 -G2 X5.613 Y6.5215 I0.107 J-0.0348 F10 -G1 X5.643 Y6.4244 -G1 X5.7483 Y6.4244 -G2 X5.7739 Y6.4214 I0 J-0.1125 -G1 X5.7739 Y7.0008 -G1 X5.7305 Y6.9693 -G1 X5.7626 Y6.8706 -G2 X5.7681 Y6.8358 I-0.107 J-0.0348 -G2 X5.5895 Y6.7448 I-0.1125 J0 -G1 X5.5055 Y6.8058 -G1 X5.4216 Y6.7448 -G2 X5.3857 Y6.7275 I-0.0661 J0.091 -G2 X5.3863 Y6.7162 I-0.1119 J-0.0112 -G2 X5.3399 Y6.6252 I-0.1125 J0 -G1 X5.2559 Y6.5642 -G1 X5.288 Y6.4655 -G2 X5.2935 Y6.4307 I-0.107 J-0.0348 -G2 X5.2934 Y6.4244 I-0.1125 J0 -G1 X5.3664 Y6.4244 -G1 X5.3985 Y6.5231 -G0 Z0.25 -G0 X0.6048 Y4.1128 -G1 Z-0.05 F30 -G2 X0.8742 Y4.1776 I0.1546 J-0.0502 F10 -G2 X0.8763 Y4.1755 I-0.1148 J-0.115 -G2 X0.8742 Y4.1776 I0.1148 J0.115 -G2 X0.8303 Y4.2673 I0.1169 J0.1129 -G2 X0.814 Y4.2777 I0.0792 J0.1419 -G1 X0.7594 Y4.3174 -G1 X0.7048 Y4.2777 -G2 X0.541 Y4.2617 I-0.0955 J0.1315 -G1 X0.541 Y4.0486 -G1 X0.584 Y4.0486 -G1 X0.6048 Y4.1128 -G1 X0.6524 Y4.0973 F10 -G2 X0.8669 Y4.0958 I0.107 J-0.0347 F10 -G1 X0.8969 Y3.9986 -G1 X0.9715 Y3.9986 -G2 X0.9714 Y4.0049 I0.1123 J0.0062 -G2 X0.9769 Y4.0397 I0.1125 J0 -G1 X1.009 Y4.1384 -G1 X0.925 Y4.1994 -G2 X0.8787 Y4.2904 I0.0661 J0.091 -G2 X0.8791 Y4.3008 I0.1125 J0 -G2 X0.8434 Y4.3182 I0.0303 J0.1083 -G1 X0.7594 Y4.3792 -G1 X0.6754 Y4.3182 -G2 X0.4968 Y4.4092 I-0.0661 J0.091 -G2 X0.5023 Y4.444 I0.1125 J0 -G1 X0.5344 Y4.5427 -G1 X0.491 Y4.5742 -G1 X0.491 Y3.9957 -G2 X0.5166 Y3.9986 I0.0255 J-0.1096 -G1 X0.6203 Y3.9986 -G1 X0.6524 Y4.0973 -G0 Z0.25 -G0 X5.3907 Y4.1776 -G1 Z-0.05 F30 -G2 X5.6608 Y4.1105 I0.1148 J-0.115 F10 -G1 X5.6799 Y4.0486 -G1 X5.7239 Y4.0486 -G1 X5.7239 Y4.2617 -G2 X5.5601 Y4.2777 I-0.0682 J0.1475 -G1 X5.5055 Y4.3174 -G1 X5.4509 Y4.2777 -G2 X5.4346 Y4.2673 I-0.0955 J0.1315 -G2 X5.3907 Y4.1776 I-0.1608 J0.0232 -G2 X5.3886 Y4.1755 I-0.1169 J0.1129 -G2 X5.3907 Y4.1776 I0.1169 J-0.1129 -G1 X5.3399 Y4.1994 F10 -G1 X5.2559 Y4.1384 F10 -G1 X5.288 Y4.0397 -G2 X5.2935 Y4.0049 I-0.107 J-0.0348 -G2 X5.2934 Y3.9986 I-0.1125 J0 -G1 X5.3664 Y3.9986 -G1 X5.3985 Y4.0974 -G2 X5.613 Y4.0958 I0.107 J-0.0348 -G1 X5.643 Y3.9986 -G1 X5.7483 Y3.9986 -G2 X5.7739 Y3.9957 I0 J-0.1125 -G1 X5.7739 Y4.5742 -G1 X5.7305 Y4.5427 -G1 X5.7626 Y4.444 -G2 X5.7681 Y4.4092 I-0.107 J-0.0348 -G2 X5.5895 Y4.3182 I-0.1125 J0 -G1 X5.5055 Y4.3792 -G1 X5.4216 Y4.3182 -G2 X5.3858 Y4.3008 I-0.0661 J0.091 -G2 X5.3863 Y4.2904 I-0.112 J-0.0104 -G2 X5.3399 Y4.1994 I-0.1125 J0 -G0 Z0.25 -G0 X5.3969 Y5.8016 -G1 Z-0.05 F30 -G2 X5.6608 Y5.7286 I0.1086 J-0.1209 F10 -G1 X5.6799 Y5.6667 -G1 X5.7239 Y5.6667 -G1 X5.7239 Y5.8789 -G2 X5.5601 Y5.8949 I-0.0682 J0.1475 -G1 X5.5055 Y5.9346 -G1 X5.4509 Y5.8949 -G2 X5.4346 Y5.8844 I-0.0955 J0.1315 -G2 X5.3969 Y5.8016 I-0.1608 J0.0232 -G2 X5.3823 Y5.7867 I-0.1232 J0.106 -G2 X5.3969 Y5.8016 I0.1232 J-0.106 -G1 X5.3399 Y5.8166 F10 -G1 X5.2559 Y5.7556 F10 -G1 X5.288 Y5.6569 -G2 X5.2935 Y5.6221 I-0.107 J-0.0348 -G2 X5.2934 Y5.6167 I-0.1125 J0 -G1 X5.3664 Y5.6167 -G1 X5.3985 Y5.7155 -G2 X5.613 Y5.7139 I0.107 J-0.0348 -G1 X5.643 Y5.6167 -G1 X5.7483 Y5.6167 -G2 X5.7739 Y5.6137 I0 J-0.1125 -G1 X5.7739 Y6.1914 -G1 X5.7305 Y6.1599 -G1 X5.7626 Y6.0612 -G2 X5.7681 Y6.0264 I-0.107 J-0.0348 -G2 X5.5895 Y5.9353 I-0.1125 J0 -G1 X5.5055 Y5.9964 -G1 X5.4216 Y5.9353 -G2 X5.3858 Y5.918 I-0.0661 J0.091 -G2 X5.3863 Y5.9076 I-0.112 J-0.0104 -G2 X5.3399 Y5.8166 I-0.1125 J0 -G0 Z0.25 -G0 X0.6048 Y5.7309 -G1 Z-0.05 F30 -G2 X0.868 Y5.8016 I0.1546 J-0.0502 F10 -G2 X0.8826 Y5.7867 I-0.1086 J-0.1209 -G2 X0.868 Y5.8016 I0.1086 J0.1209 -G2 X0.8303 Y5.8844 I0.1232 J0.106 -G2 X0.814 Y5.8949 I0.0792 J0.1419 -G1 X0.7594 Y5.9346 -G1 X0.7048 Y5.8949 -G2 X0.541 Y5.8789 I-0.0955 J0.1315 -G1 X0.541 Y5.6667 -G1 X0.584 Y5.6667 -G1 X0.6048 Y5.7309 -G1 X0.6524 Y5.7155 F10 -G2 X0.8669 Y5.714 I0.107 J-0.0347 F10 -G1 X0.8969 Y5.6167 -G1 X0.9715 Y5.6167 -G2 X0.9714 Y5.6221 I0.1124 J0.0054 -G2 X0.9769 Y5.6569 I0.1125 J0 -G1 X1.009 Y5.7556 -G1 X0.925 Y5.8166 -G2 X0.8787 Y5.9076 I0.0661 J0.091 -G2 X0.8791 Y5.918 I0.1125 J0 -G2 X0.8434 Y5.9353 I0.0303 J0.1083 -G1 X0.7594 Y5.9964 -G1 X0.6754 Y5.9353 -G2 X0.4968 Y6.0264 I-0.0661 J0.091 -G2 X0.5023 Y6.0612 I0.1125 J0 -G1 X0.5344 Y6.1599 -G1 X0.491 Y6.1914 -G1 X0.491 Y5.6137 -G2 X0.5166 Y5.6167 I0.0255 J-0.1096 -G1 X0.6203 Y5.6167 -G1 X0.6524 Y5.7155 -G0 Z0.25 -G0 X3.0628 Y3.7486 -G1 Z-0.05 F30 -G1 X3.2022 Y3.7486 F10 -G2 X3.1586 Y3.8323 I0.162 J0.1375 -G2 X3.1578 Y3.8329 I0.124 J0.1726 -G1 X3.1324 Y3.8513 -G1 X3.1072 Y3.833 -G2 X3.1063 Y3.8323 I-0.1249 J0.1719 -G2 X3.0628 Y3.7486 I-0.2056 J0.0538 -G1 X2.9963 Y3.7547 F10 -G1 X2.9416 Y3.715 F10 -G1 X2.9469 Y3.6986 -G1 X3.318 Y3.6986 -G1 X3.3233 Y3.715 -G1 X3.2687 Y3.7547 -G2 X3.2033 Y3.8631 I0.0955 J0.1315 -G2 X3.1871 Y3.8734 I0.0793 J0.1418 -G1 X3.1324 Y3.9131 -G1 X3.0778 Y3.8734 -G2 X3.0616 Y3.8631 I-0.0955 J0.1315 -G2 X2.9963 Y3.7547 I-0.1609 J0.0231 -G1 X2.9669 Y3.7951 F10 -G1 X2.8829 Y3.7341 F10 -G1 X2.9106 Y3.6486 -G1 X3.3543 Y3.6486 -G1 X3.382 Y3.7341 -G1 X3.298 Y3.7951 -G2 X3.2517 Y3.8861 I0.0661 J0.091 -G2 X3.2522 Y3.8966 I0.1125 J0 -G2 X3.2165 Y3.9139 I0.0305 J0.1083 -G1 X3.1324 Y3.9749 -G1 X3.0484 Y3.9139 -G2 X3.0127 Y3.8966 I-0.0661 J0.091 -G2 X3.0132 Y3.8861 I-0.112 J-0.0104 -G2 X2.9669 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X4.9612 Y3.7486 -G1 Z-0.05 F30 -G1 X5.1006 Y3.7486 F10 -G2 X5.057 Y3.8323 I0.162 J0.1375 -G2 X5.0562 Y3.8329 I0.124 J0.1726 -G1 X5.0309 Y3.8513 -G1 X5.0056 Y3.833 -G2 X5.0047 Y3.8323 I-0.1249 J0.1719 -G2 X4.9612 Y3.7486 I-0.2056 J0.0538 -G1 X4.8947 Y3.7547 F10 -G1 X4.8401 Y3.715 F10 -G1 X4.8454 Y3.6986 -G1 X5.2164 Y3.6986 -G1 X5.2217 Y3.715 -G1 X5.1671 Y3.7547 -G2 X5.1018 Y3.8631 I0.0955 J0.1315 -G2 X5.0856 Y3.8734 I0.0793 J0.1418 -G1 X5.0309 Y3.9131 -G1 X4.9763 Y3.8734 -G2 X4.96 Y3.8631 I-0.0955 J0.1315 -G2 X4.8947 Y3.7547 I-0.1609 J0.0231 -G1 X4.8653 Y3.7951 F10 -G1 X4.7813 Y3.7341 F10 -G1 X4.8091 Y3.6486 -G1 X5.2527 Y3.6486 -G1 X5.2805 Y3.7341 -G1 X5.1965 Y3.7951 -G2 X5.1501 Y3.8861 I0.0661 J0.091 -G2 X5.1506 Y3.8966 I0.1125 J0 -G2 X5.115 Y3.9139 I0.0305 J0.1083 -G1 X5.0309 Y3.9749 -G1 X4.9469 Y3.9139 -G2 X4.9112 Y3.8966 I-0.0661 J0.091 -G2 X4.9117 Y3.8861 I-0.112 J-0.0104 -G2 X4.8653 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X1.1643 Y3.7486 -G1 Z-0.05 F30 -G1 X1.3037 Y3.7486 F10 -G2 X1.2602 Y3.8323 I0.162 J0.1375 -G2 X1.2593 Y3.833 I0.124 J0.1726 -G1 X1.234 Y3.8513 -G1 X1.2087 Y3.8329 -G2 X1.2079 Y3.8323 I-0.1249 J0.172 -G2 X1.1643 Y3.7486 I-0.2056 J0.0538 -G1 X1.0978 Y3.7547 F10 -G1 X1.0432 Y3.715 F10 -G1 X1.0485 Y3.6986 -G1 X1.4195 Y3.6986 -G1 X1.4248 Y3.715 -G1 X1.3702 Y3.7547 -G2 X1.3049 Y3.8631 I0.0955 J0.1315 -G2 X1.2887 Y3.8734 I0.0793 J0.1418 -G1 X1.234 Y3.9131 -G1 X1.1793 Y3.8734 -G2 X1.1631 Y3.8631 I-0.0955 J0.1315 -G2 X1.0978 Y3.7547 I-0.1609 J0.0231 -G1 X1.0684 Y3.7951 F10 -G1 X0.9844 Y3.7341 F10 -G1 X1.0122 Y3.6486 -G1 X1.4559 Y3.6486 -G1 X1.4836 Y3.7341 -G1 X1.3996 Y3.7951 -G2 X1.3532 Y3.8861 I0.0661 J0.091 -G2 X1.3537 Y3.8966 I0.1125 J0 -G2 X1.318 Y3.9139 I0.0305 J0.1083 -G1 X1.234 Y3.9749 -G1 X1.15 Y3.9139 -G2 X1.1143 Y3.8966 I-0.0661 J0.091 -G2 X1.1148 Y3.8861 I-0.112 J-0.0104 -G2 X1.0684 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X4.0119 Y3.7486 -G1 Z-0.05 F30 -G1 X4.1514 Y3.7486 F10 -G2 X4.1079 Y3.8322 I0.162 J0.1375 -G2 X4.1069 Y3.833 I0.1239 J0.1727 -G1 X4.0817 Y3.8513 -G1 X4.0565 Y3.833 -G2 X4.0555 Y3.8322 I-0.1249 J0.1719 -G2 X4.0119 Y3.7486 I-0.2055 J0.0539 -G1 X3.9454 Y3.7547 F10 -G1 X3.8909 Y3.715 F10 -G1 X3.8962 Y3.6986 -G1 X4.2672 Y3.6986 -G1 X4.2725 Y3.715 -G1 X4.2179 Y3.7547 -G2 X4.1526 Y3.863 I0.0955 J0.1315 -G2 X4.1363 Y3.8734 I0.0792 J0.1419 -G1 X4.0817 Y3.9131 -G1 X4.0271 Y3.8734 -G2 X4.0107 Y3.863 I-0.0955 J0.1315 -G2 X3.9454 Y3.7547 I-0.1608 J0.0232 -G1 X3.916 Y3.7951 F10 -G1 X3.8321 Y3.7341 F10 -G1 X3.8599 Y3.6486 -G1 X4.3035 Y3.6486 -G1 X4.3313 Y3.7341 -G1 X4.2473 Y3.7951 -G2 X4.2009 Y3.8861 I0.0661 J0.091 -G2 X4.2014 Y3.8966 I0.1125 J0 -G2 X4.1656 Y3.9139 I0.0303 J0.1083 -G1 X4.0817 Y3.9749 -G1 X3.9977 Y3.9139 -G2 X3.9619 Y3.8966 I-0.0661 J0.091 -G2 X3.9624 Y3.8861 I-0.112 J-0.0104 -G2 X3.916 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X2.1135 Y3.7486 -G1 Z-0.05 F30 -G1 X2.253 Y3.7486 F10 -G2 X2.2095 Y3.8322 I0.162 J0.1375 -G2 X2.2084 Y3.833 I0.1239 J0.1727 -G1 X2.1832 Y3.8513 -G1 X2.158 Y3.833 -G2 X2.157 Y3.8322 I-0.1249 J0.1719 -G2 X2.1135 Y3.7486 I-0.2055 J0.0539 -G1 X2.047 Y3.7547 F10 -G1 X1.9924 Y3.715 F10 -G1 X1.9978 Y3.6986 -G1 X2.3687 Y3.6986 -G1 X2.3741 Y3.715 -G1 X2.3195 Y3.7547 -G2 X2.2542 Y3.863 I0.0955 J0.1315 -G2 X2.2378 Y3.8734 I0.0792 J0.1419 -G1 X2.1832 Y3.9131 -G1 X2.1286 Y3.8734 -G2 X2.1123 Y3.863 I-0.0955 J0.1315 -G2 X2.047 Y3.7547 I-0.1608 J0.0232 -G1 X2.0176 Y3.7951 F10 -G1 X1.9336 Y3.7341 F10 -G1 X1.9614 Y3.6486 -G1 X2.405 Y3.6486 -G1 X2.4328 Y3.7341 -G1 X2.3489 Y3.7951 -G2 X2.3025 Y3.8861 I0.0661 J0.091 -G2 X2.303 Y3.8966 I0.1125 J0 -G2 X2.2672 Y3.9139 I0.0303 J0.1083 -G1 X2.1832 Y3.9749 -G1 X2.0993 Y3.9139 -G2 X2.0635 Y3.8966 I-0.0661 J0.091 -G2 X2.064 Y3.8861 I-0.112 J-0.0104 -G2 X2.0176 Y3.7951 I-0.1125 J0 -G0 Z0.25 -G0 X1.6001 Y5.8016 -G1 Z-0.05 F30 -G2 X1.8168 Y5.802 I0.1086 J-0.1209 F10 -G2 X1.7795 Y5.8845 I0.1235 J0.1056 -G2 X1.7632 Y5.8949 I0.0793 J0.1418 -G1 X1.7087 Y5.9346 -G1 X1.6541 Y5.8949 -G2 X1.6377 Y5.8844 I-0.0955 J0.1315 -G2 X1.6001 Y5.8016 I-0.1608 J0.0232 -G2 X1.5855 Y5.7867 I-0.1232 J0.106 -G2 X1.6001 Y5.8016 I0.1232 J-0.106 -G0 Z0.25 -G0 X1.8994 Y5.7365 -G1 Z-0.05 F30 -G1 X1.8448 Y5.7761 F10 -G2 X1.8322 Y5.7863 I0.0955 J0.1315 -G2 X1.8639 Y5.7286 I-0.1235 J-0.1056 -G1 X1.88 Y5.6766 -G1 X1.8994 Y5.7365 -G0 Z0.25 -G0 X1.9582 Y5.7556 -G1 Z-0.05 F30 -G1 X1.8742 Y5.8166 F10 -G2 X1.8278 Y5.9076 I0.0661 J0.091 -G2 X1.8283 Y5.9181 I0.1125 J0 -G2 X1.7926 Y5.9353 I0.0305 J0.1083 -G1 X1.7087 Y5.9964 -G1 X1.6247 Y5.9353 -G2 X1.5889 Y5.918 I-0.0661 J0.091 -G2 X1.5894 Y5.9076 I-0.112 J-0.0104 -G2 X1.543 Y5.8166 I-0.1125 J0 -G1 X1.4591 Y5.7556 -G1 X1.4912 Y5.6569 -G2 X1.4967 Y5.6221 I-0.107 J-0.0348 -G2 X1.4965 Y5.6167 I-0.1125 J0 -G1 X1.5695 Y5.6167 -G1 X1.6017 Y5.7155 -G2 X1.8162 Y5.7139 I0.107 J-0.0348 -G1 X1.8462 Y5.6167 -G1 X1.9208 Y5.6167 -G2 X1.9206 Y5.6221 I0.1124 J0.0054 -G2 X1.9261 Y5.6568 I0.1125 J0 -G1 X1.9582 Y5.7556 -G0 Z0.25 -G0 X3.4985 Y5.8016 -G1 Z-0.05 F30 -G2 X3.7152 Y5.802 I0.1086 J-0.1209 F10 -G2 X3.6779 Y5.8845 I0.1235 J0.1056 -G2 X3.6617 Y5.8949 I0.0793 J0.1418 -G1 X3.6071 Y5.9346 -G1 X3.5525 Y5.8949 -G2 X3.5362 Y5.8844 I-0.0955 J0.1315 -G2 X3.4985 Y5.8016 I-0.1608 J0.0232 -G2 X3.4839 Y5.7867 I-0.1232 J0.106 -G2 X3.4985 Y5.8016 I0.1232 J-0.106 -G0 Z0.25 -G0 X3.7979 Y5.7365 -G1 Z-0.05 F30 -G1 X3.7432 Y5.7761 F10 -G2 X3.7306 Y5.7863 I0.0955 J0.1315 -G2 X3.7624 Y5.7286 I-0.1235 J-0.1056 -G1 X3.7784 Y5.6766 -G1 X3.7979 Y5.7365 -G0 Z0.25 -G0 X3.8566 Y5.7556 -G1 Z-0.05 F30 -G1 X3.7726 Y5.8166 F10 -G2 X3.7263 Y5.9076 I0.0661 J0.091 -G2 X3.7267 Y5.9181 I0.1125 J0 -G2 X3.6911 Y5.9353 I0.0305 J0.1083 -G1 X3.6071 Y5.9964 -G1 X3.5231 Y5.9353 -G2 X3.4873 Y5.918 I-0.0661 J0.091 -G2 X3.4878 Y5.9076 I-0.112 J-0.0104 -G2 X3.4414 Y5.8166 I-0.1125 J0 -G1 X3.3575 Y5.7556 -G1 X3.3896 Y5.6569 -G2 X3.3951 Y5.6221 I-0.107 J-0.0348 -G2 X3.395 Y5.6167 I-0.1125 J0 -G1 X3.468 Y5.6167 -G1 X3.5001 Y5.7155 -G2 X3.7146 Y5.7139 I0.107 J-0.0348 -G1 X3.7446 Y5.6167 -G1 X3.8192 Y5.6167 -G2 X3.8191 Y5.6221 I0.1124 J0.0054 -G2 X3.8246 Y5.6568 I0.1125 J0 -G1 X3.8566 Y5.7556 -G0 Z0.25 -G0 X4.4481 Y5.802 -G1 Z-0.05 F30 -G2 X4.6648 Y5.8016 I0.1081 J-0.1213 F10 -G2 X4.6272 Y5.8844 I0.1232 J0.106 -G2 X4.6108 Y5.8949 I0.0792 J0.1419 -G1 X4.5563 Y5.9346 -G1 X4.5017 Y5.8949 -G2 X4.4854 Y5.8845 I-0.0955 J0.1315 -G2 X4.4481 Y5.802 I-0.1609 J0.0231 -G2 X4.4327 Y5.7863 I-0.1235 J0.1056 -G2 X4.4481 Y5.802 I0.1235 J-0.1056 -G0 Z0.25 -G0 X4.7471 Y5.7365 -G1 Z-0.05 F30 -G1 X4.6925 Y5.7761 F10 -G2 X4.6794 Y5.7867 I0.0955 J0.1315 -G2 X4.7115 Y5.7287 I-0.1232 J-0.106 -G1 X4.7276 Y5.6767 -G1 X4.7471 Y5.7365 -G0 Z0.25 -G0 X4.8059 Y5.7556 -G1 Z-0.05 F30 -G1 X4.7219 Y5.8166 F10 -G2 X4.6755 Y5.9076 I0.0661 J0.091 -G2 X4.676 Y5.918 I0.1125 J0 -G2 X4.6402 Y5.9353 I0.0303 J0.1083 -G1 X4.5563 Y5.9964 -G1 X4.4723 Y5.9353 -G2 X4.4366 Y5.9181 I-0.0661 J0.091 -G2 X4.4371 Y5.9076 I-0.112 J-0.0104 -G2 X4.3907 Y5.8166 I-0.1125 J0 -G1 X4.3067 Y5.7556 -G1 X4.3388 Y5.6568 -G2 X4.3443 Y5.6221 I-0.107 J-0.0347 -G2 X4.3441 Y5.6167 I-0.1125 J0 -G1 X4.4172 Y5.6167 -G1 X4.4492 Y5.7155 -G2 X4.6637 Y5.714 I0.107 J-0.0347 -G1 X4.6938 Y5.6167 -G1 X4.7684 Y5.6167 -G2 X4.7682 Y5.6221 I0.1124 J0.0054 -G2 X4.7738 Y5.6569 I0.1125 J0 -G1 X4.8059 Y5.7556 -G0 Z0.25 -G0 X2.5497 Y5.802 -G1 Z-0.05 F30 -G2 X2.7664 Y5.8016 I0.1081 J-0.1213 F10 -G2 X2.7287 Y5.8844 I0.1232 J0.106 -G2 X2.7124 Y5.8949 I0.0792 J0.1419 -G1 X2.6578 Y5.9346 -G1 X2.6032 Y5.8949 -G2 X2.587 Y5.8845 I-0.0955 J0.1315 -G2 X2.5497 Y5.802 I-0.1609 J0.0231 -G2 X2.5343 Y5.7863 I-0.1235 J0.1056 -G2 X2.5497 Y5.802 I0.1235 J-0.1056 -G0 Z0.25 -G0 X2.8486 Y5.7365 -G1 Z-0.05 F30 -G1 X2.7941 Y5.7761 F10 -G2 X2.781 Y5.7867 I0.0955 J0.1315 -G2 X2.8131 Y5.7287 I-0.1232 J-0.106 -G1 X2.8292 Y5.6767 -G1 X2.8486 Y5.7365 -G0 Z0.25 -G0 X2.9074 Y5.7556 -G1 Z-0.05 F30 -G1 X2.8235 Y5.8166 F10 -G2 X2.7771 Y5.9076 I0.0661 J0.091 -G2 X2.7776 Y5.918 I0.1125 J0 -G2 X2.7418 Y5.9353 I0.0303 J0.1083 -G1 X2.6578 Y5.9964 -G1 X2.5738 Y5.9353 -G2 X2.5382 Y5.9181 I-0.0661 J0.091 -G2 X2.5387 Y5.9076 I-0.112 J-0.0104 -G2 X2.4923 Y5.8166 I-0.1125 J0 -G1 X2.4083 Y5.7556 -G1 X2.4403 Y5.6568 -G2 X2.4458 Y5.6221 I-0.107 J-0.0347 -G2 X2.4457 Y5.6167 I-0.1125 J0 -G1 X2.5188 Y5.6167 -G1 X2.5508 Y5.7155 -G2 X2.7653 Y5.714 I0.107 J-0.0347 -G1 X2.7954 Y5.6167 -G1 X2.8699 Y5.6167 -G2 X2.8698 Y5.6221 I0.1124 J0.0054 -G2 X2.8753 Y5.6569 I0.1125 J0 -G1 X2.9074 Y5.7556 -G0 Z0.25 -G0 X1.1192 Y6.199 -G1 Z-0.05 F30 -G2 X1.3473 Y6.2007 I0.1148 J-0.115 F10 -G2 X1.3049 Y6.2889 I0.1185 J0.1112 -G2 X1.2887 Y6.2992 I0.0793 J0.1418 -G1 X1.234 Y6.339 -G1 X1.1794 Y6.2993 -G2 X1.1632 Y6.2889 I-0.0955 J0.1315 -G2 X1.1192 Y6.199 I-0.1609 J0.023 -G2 X1.1171 Y6.1969 I-0.1169 J0.1129 -G2 X1.1192 Y6.199 I0.1169 J-0.1129 -G0 Z0.25 -G0 X1.3525 Y6.1953 -G1 Z-0.05 F30 -G2 X1.3893 Y6.132 I-0.1185 J-0.1112 F10 -G1 X1.4053 Y6.0804 -G1 X1.4248 Y6.1407 -G1 X1.3702 Y6.1804 -G2 X1.3525 Y6.1953 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.3996 Y6.2209 -G1 Z-0.05 F30 -G2 X1.3532 Y6.3119 I0.0661 J0.091 F10 -G2 X1.3537 Y6.3224 I0.1125 J0 -G2 X1.3181 Y6.3397 I0.0304 J0.1083 -G1 X1.234 Y6.4007 -G1 X1.15 Y6.3397 -G2 X1.1143 Y6.3224 I-0.0661 J0.091 -G2 X1.1148 Y6.3119 I-0.112 J-0.0106 -G2 X1.0684 Y6.2209 I-0.1125 J0 -G1 X0.9844 Y6.1598 -G1 X1.0165 Y6.0611 -G2 X1.022 Y6.0264 I-0.107 J-0.0347 -G2 X1.0218 Y6.0201 I-0.1125 J0 -G1 X1.095 Y6.0201 -G1 X1.1271 Y6.1189 -G2 X1.3416 Y6.1172 I0.107 J-0.0348 -G1 X1.3716 Y6.0201 -G1 X1.4462 Y6.0201 -G2 X1.446 Y6.0264 I0.1123 J0.0062 -G2 X1.4515 Y6.0611 I0.1125 J0 -G1 X1.4836 Y6.1598 -G1 X1.3996 Y6.2209 -G0 Z0.25 -G0 X1.5938 Y4.1776 -G1 Z-0.05 F30 -G2 X1.8218 Y4.1792 I0.1148 J-0.115 F10 -G2 X1.7795 Y4.2673 I0.1185 J0.1112 -G2 X1.7632 Y4.2777 I0.0793 J0.1418 -G1 X1.7087 Y4.3174 -G1 X1.6541 Y4.2777 -G2 X1.6377 Y4.2673 I-0.0955 J0.1315 -G2 X1.5938 Y4.1776 I-0.1608 J0.0232 -G2 X1.5917 Y4.1755 I-0.1169 J0.1129 -G2 X1.5938 Y4.1776 I0.1169 J-0.1129 -G0 Z0.25 -G0 X1.8271 Y4.1738 -G1 Z-0.05 F30 -G2 X1.8639 Y4.1105 I-0.1185 J-0.1112 F10 -G1 X1.8798 Y4.059 -G1 X1.8994 Y4.1193 -G1 X1.8448 Y4.159 -G2 X1.8271 Y4.1738 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.8742 Y4.1994 -G1 Z-0.05 F30 -G2 X1.8278 Y4.2904 I0.0661 J0.091 F10 -G2 X1.8283 Y4.3009 I0.1125 J0 -G2 X1.7926 Y4.3182 I0.0305 J0.1083 -G1 X1.7087 Y4.3792 -G1 X1.6247 Y4.3182 -G2 X1.5889 Y4.3008 I-0.0661 J0.091 -G2 X1.5894 Y4.2904 I-0.112 J-0.0104 -G2 X1.543 Y4.1994 I-0.1125 J0 -G1 X1.4591 Y4.1384 -G1 X1.4912 Y4.0397 -G2 X1.4967 Y4.0049 I-0.107 J-0.0348 -G2 X1.4965 Y3.9986 I-0.1125 J0 -G1 X1.5695 Y3.9986 -G1 X1.6017 Y4.0974 -G2 X1.8161 Y4.0958 I0.107 J-0.0348 -G1 X1.8461 Y3.9986 -G1 X1.9208 Y3.9986 -G2 X1.9206 Y4.0049 I0.1123 J0.0062 -G2 X1.9261 Y4.0396 I0.1125 J0 -G1 X1.9582 Y4.1384 -G1 X1.8742 Y4.1994 -G0 Z0.25 -G0 X3.4526 Y4.9214 -G1 Z-0.05 F30 -G2 X3.7218 Y4.9862 I0.1545 J-0.0503 F10 -G2 X3.6778 Y5.0769 I0.1169 J0.1129 -G2 X3.6617 Y5.0872 I0.0794 J0.1418 -G1 X3.6071 Y5.1268 -G1 X3.5525 Y5.0872 -G2 X3.5363 Y5.0768 I-0.0955 J0.1315 -G2 X3.4708 Y4.9676 I-0.161 J0.0223 -G1 X3.4163 Y4.928 -G1 X3.4355 Y4.8689 -G1 X3.4526 Y4.9214 -G0 Z0.25 -G0 X3.724 Y4.984 -G1 Z-0.05 F30 -G2 X3.7624 Y4.9191 I-0.1169 J-0.1129 F10 -G1 X3.7783 Y4.8676 -G1 X3.7979 Y4.9279 -G1 X3.7432 Y4.9676 -G2 X3.724 Y4.984 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.7726 Y5.008 -G1 Z-0.05 F30 -G2 X3.7263 Y5.0991 I0.0661 J0.091 F10 -G2 X3.7268 Y5.1103 I0.1125 J0 -G2 X3.6911 Y5.1276 I0.0304 J0.1083 -G1 X3.6071 Y5.1886 -G1 X3.5231 Y5.1276 -G2 X3.4873 Y5.1103 I-0.0661 J0.091 -G2 X3.4878 Y5.0991 I-0.1119 J-0.0112 -G2 X3.4414 Y5.008 I-0.1125 J0 -G1 X3.3575 Y4.947 -G1 X3.3896 Y4.8483 -G2 X3.3951 Y4.8135 I-0.107 J-0.0348 -G2 X3.3949 Y4.8072 I-0.1125 J0 -G1 X3.468 Y4.8072 -G1 X3.5001 Y4.9059 -G2 X3.7146 Y4.9043 I0.107 J-0.0348 -G1 X3.7446 Y4.8072 -G1 X3.8192 Y4.8072 -G2 X3.8191 Y4.8135 I0.1123 J0.0064 -G2 X3.8246 Y4.8483 I0.1125 J0 -G1 X3.8566 Y4.947 -G1 X3.7726 Y5.008 -G0 Z0.25 -G0 X1.1192 Y4.5818 -G1 Z-0.05 F30 -G2 X1.3473 Y4.5835 I0.1148 J-0.115 F10 -G2 X1.3049 Y4.6717 I0.1185 J0.1112 -G2 X1.2887 Y4.682 I0.0793 J0.1418 -G1 X1.234 Y4.7218 -G1 X1.1794 Y4.6821 -G2 X1.1632 Y4.6717 I-0.0955 J0.1315 -G2 X1.1192 Y4.5818 I-0.1609 J0.023 -G2 X1.1171 Y4.5797 I-0.1169 J0.1129 -G2 X1.1192 Y4.5818 I0.1169 J-0.1129 -G0 Z0.25 -G0 X1.3525 Y4.5781 -G1 Z-0.05 F30 -G2 X1.3893 Y4.5148 I-0.1185 J-0.1112 F10 -G1 X1.4053 Y4.4632 -G1 X1.4248 Y4.5235 -G1 X1.3702 Y4.5632 -G2 X1.3525 Y4.5781 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.3996 Y4.6037 -G1 Z-0.05 F30 -G2 X1.3532 Y4.6947 I0.0661 J0.091 F10 -G2 X1.3537 Y4.7052 I0.1125 J0 -G2 X1.3181 Y4.7225 I0.0304 J0.1083 -G1 X1.234 Y4.7836 -G1 X1.15 Y4.7225 -G2 X1.1143 Y4.7052 I-0.0661 J0.091 -G2 X1.1148 Y4.6947 I-0.112 J-0.0106 -G2 X1.0684 Y4.6037 I-0.1125 J0 -G1 X0.9844 Y4.5426 -G1 X1.0165 Y4.4439 -G2 X1.022 Y4.4092 I-0.107 J-0.0347 -G2 X1.0218 Y4.4029 I-0.1125 J0 -G1 X1.095 Y4.4029 -G1 X1.1271 Y4.5017 -G2 X1.3416 Y4.5001 I0.107 J-0.0348 -G1 X1.3716 Y4.4029 -G1 X1.4462 Y4.4029 -G2 X1.446 Y4.4092 I0.1123 J0.0062 -G2 X1.4515 Y4.4439 I0.1125 J0 -G1 X1.4836 Y4.5426 -G1 X1.3996 Y4.6037 -G0 Z0.25 -G0 X1.5541 Y6.5386 -G1 Z-0.05 F30 -G2 X1.8234 Y6.6034 I0.1545 J-0.0503 F10 -G2 X1.7793 Y6.6941 I0.1169 J0.1129 -G2 X1.7632 Y6.7044 I0.0794 J0.1418 -G1 X1.7087 Y6.744 -G1 X1.6541 Y6.7044 -G2 X1.6379 Y6.694 I-0.0955 J0.1315 -G2 X1.5724 Y6.5848 I-0.161 J0.0223 -G1 X1.5178 Y6.5451 -G1 X1.537 Y6.4861 -G1 X1.5541 Y6.5386 -G0 Z0.25 -G0 X1.8256 Y6.6012 -G1 Z-0.05 F30 -G2 X1.8639 Y6.5363 I-0.1169 J-0.1129 F10 -G1 X1.8798 Y6.4848 -G1 X1.8994 Y6.5451 -G1 X1.8448 Y6.5848 -G2 X1.8256 Y6.6012 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.8742 Y6.6252 -G1 Z-0.05 F30 -G2 X1.8278 Y6.7162 I0.0661 J0.091 F10 -G2 X1.8284 Y6.7275 I0.1125 J0 -G2 X1.7926 Y6.7448 I0.0304 J0.1083 -G1 X1.7087 Y6.8058 -G1 X1.6247 Y6.7448 -G2 X1.5888 Y6.7275 I-0.0661 J0.091 -G2 X1.5894 Y6.7162 I-0.1119 J-0.0112 -G2 X1.543 Y6.6252 I-0.1125 J0 -G1 X1.4591 Y6.5642 -G1 X1.4912 Y6.4655 -G2 X1.4967 Y6.4307 I-0.107 J-0.0348 -G2 X1.4965 Y6.4244 I-0.1125 J0 -G1 X1.5695 Y6.4244 -G1 X1.6017 Y6.5231 -G2 X1.8161 Y6.5215 I0.107 J-0.0348 -G1 X1.8461 Y6.4244 -G1 X1.9208 Y6.4244 -G2 X1.9206 Y6.4307 I0.1123 J0.0064 -G2 X1.9261 Y6.4655 I0.1125 J0 -G1 X1.9582 Y6.5642 -G1 X1.8742 Y6.6252 -G0 Z0.25 -G0 X1.5541 Y4.9214 -G1 Z-0.05 F30 -G2 X1.8234 Y4.9862 I0.1545 J-0.0503 F10 -G2 X1.7793 Y5.0769 I0.1169 J0.1129 -G2 X1.7632 Y5.0872 I0.0794 J0.1418 -G1 X1.7087 Y5.1268 -G1 X1.6541 Y5.0872 -G2 X1.6379 Y5.0768 I-0.0955 J0.1315 -G2 X1.5724 Y4.9676 I-0.161 J0.0223 -G1 X1.5178 Y4.928 -G1 X1.537 Y4.8689 -G1 X1.5541 Y4.9214 -G0 Z0.25 -G0 X1.8256 Y4.984 -G1 Z-0.05 F30 -G2 X1.8639 Y4.9191 I-0.1169 J-0.1129 F10 -G1 X1.8798 Y4.8676 -G1 X1.8994 Y4.9279 -G1 X1.8448 Y4.9676 -G2 X1.8256 Y4.984 I0.0955 J0.1315 -G0 Z0.25 -G0 X1.8742 Y5.008 -G1 Z-0.05 F30 -G2 X1.8278 Y5.0991 I0.0661 J0.091 F10 -G2 X1.8284 Y5.1103 I0.1125 J0 -G2 X1.7926 Y5.1276 I0.0304 J0.1083 -G1 X1.7087 Y5.1886 -G1 X1.6247 Y5.1276 -G2 X1.5888 Y5.1103 I-0.0661 J0.091 -G2 X1.5894 Y5.0991 I-0.1119 J-0.0112 -G2 X1.543 Y5.008 I-0.1125 J0 -G1 X1.4591 Y4.947 -G1 X1.4912 Y4.8483 -G2 X1.4967 Y4.8135 I-0.107 J-0.0348 -G2 X1.4965 Y4.8072 I-0.1125 J0 -G1 X1.5695 Y4.8072 -G1 X1.6017 Y4.9059 -G2 X1.8161 Y4.9043 I0.107 J-0.0348 -G1 X1.8461 Y4.8072 -G1 X1.9208 Y4.8072 -G2 X1.9206 Y4.8135 I0.1123 J0.0064 -G2 X1.9261 Y4.8483 I0.1125 J0 -G1 X1.9582 Y4.947 -G1 X1.8742 Y5.008 -G0 Z0.25 -G0 X3.4526 Y6.5386 -G1 Z-0.05 F30 -G2 X3.7218 Y6.6034 I0.1545 J-0.0503 F10 -G2 X3.6778 Y6.6941 I0.1169 J0.1129 -G2 X3.6617 Y6.7044 I0.0794 J0.1418 -G1 X3.6071 Y6.744 -G1 X3.5525 Y6.7044 -G2 X3.5363 Y6.694 I-0.0955 J0.1315 -G2 X3.4708 Y6.5848 I-0.161 J0.0223 -G1 X3.4163 Y6.5451 -G1 X3.4355 Y6.4861 -G1 X3.4526 Y6.5386 -G0 Z0.25 -G0 X3.724 Y6.6012 -G1 Z-0.05 F30 -G2 X3.7624 Y6.5363 I-0.1169 J-0.1129 F10 -G1 X3.7783 Y6.4848 -G1 X3.7979 Y6.5451 -G1 X3.7432 Y6.5848 -G2 X3.724 Y6.6012 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.7726 Y6.6252 -G1 Z-0.05 F30 -G2 X3.7263 Y6.7162 I0.0661 J0.091 F10 -G2 X3.7268 Y6.7275 I0.1125 J0 -G2 X3.6911 Y6.7448 I0.0304 J0.1083 -G1 X3.6071 Y6.8058 -G1 X3.5231 Y6.7448 -G2 X3.4873 Y6.7275 I-0.0661 J0.091 -G2 X3.4878 Y6.7162 I-0.1119 J-0.0112 -G2 X3.4414 Y6.6252 I-0.1125 J0 -G1 X3.3575 Y6.5642 -G1 X3.3896 Y6.4655 -G2 X3.3951 Y6.4307 I-0.107 J-0.0348 -G2 X3.3949 Y6.4244 I-0.1125 J0 -G1 X3.468 Y6.4244 -G1 X3.5001 Y6.5231 -G2 X3.7146 Y6.5215 I0.107 J-0.0348 -G1 X3.7446 Y6.4244 -G1 X3.8192 Y6.4244 -G2 X3.8191 Y6.4307 I0.1123 J0.0064 -G2 X3.8246 Y6.4655 I0.1125 J0 -G1 X3.8566 Y6.5642 -G1 X3.7726 Y6.6252 -G0 Z0.25 -G0 X3.4922 Y4.1776 -G1 Z-0.05 F30 -G2 X3.7203 Y4.1792 I0.1148 J-0.115 F10 -G2 X3.6779 Y4.2673 I0.1185 J0.1112 -G2 X3.6617 Y4.2777 I0.0793 J0.1418 -G1 X3.6071 Y4.3174 -G1 X3.5525 Y4.2777 -G2 X3.5362 Y4.2673 I-0.0955 J0.1315 -G2 X3.4922 Y4.1776 I-0.1608 J0.0232 -G2 X3.4902 Y4.1755 I-0.1169 J0.1129 -G2 X3.4922 Y4.1776 I0.1169 J-0.1129 -G0 Z0.25 -G0 X3.7256 Y4.1738 -G1 Z-0.05 F30 -G2 X3.7624 Y4.1105 I-0.1185 J-0.1112 F10 -G1 X3.7783 Y4.059 -G1 X3.7979 Y4.1193 -G1 X3.7432 Y4.159 -G2 X3.7256 Y4.1738 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.7726 Y4.1994 -G1 Z-0.05 F30 -G2 X3.7263 Y4.2904 I0.0661 J0.091 F10 -G2 X3.7267 Y4.3009 I0.1125 J0 -G2 X3.6911 Y4.3182 I0.0305 J0.1083 -G1 X3.6071 Y4.3792 -G1 X3.5231 Y4.3182 -G2 X3.4873 Y4.3008 I-0.0661 J0.091 -G2 X3.4878 Y4.2904 I-0.112 J-0.0104 -G2 X3.4414 Y4.1994 I-0.1125 J0 -G1 X3.3575 Y4.1384 -G1 X3.3896 Y4.0397 -G2 X3.3951 Y4.0049 I-0.107 J-0.0348 -G2 X3.3949 Y3.9986 I-0.1125 J0 -G1 X3.468 Y3.9986 -G1 X3.5001 Y4.0974 -G2 X3.7146 Y4.0958 I0.107 J-0.0348 -G1 X3.7446 Y3.9986 -G1 X3.8192 Y3.9986 -G2 X3.8191 Y4.0049 I0.1123 J0.0062 -G2 X3.8246 Y4.0396 I0.1125 J0 -G1 X3.8566 Y4.1384 -G1 X3.7726 Y4.1994 -G0 Z0.25 -G0 X4.9177 Y4.5835 -G1 Z-0.05 F30 -G2 X5.1457 Y4.5818 I0.1132 J-0.1166 F10 -G2 X5.1017 Y4.6717 I0.1169 J0.1129 -G2 X5.0856 Y4.682 I0.0793 J0.1418 -G1 X5.0309 Y4.7218 -G1 X4.9763 Y4.6821 -G2 X4.96 Y4.6717 I-0.0955 J0.1315 -G2 X4.9177 Y4.5835 I-0.1609 J0.023 -G2 X4.9124 Y4.5781 I-0.1185 J0.1112 -G2 X4.9177 Y4.5835 I0.1185 J-0.1112 -G0 Z0.25 -G0 X5.1478 Y4.5797 -G1 Z-0.05 F30 -G2 X5.1861 Y4.5149 I-0.1169 J-0.1129 F10 -G1 X5.2021 Y4.4631 -G1 X5.2217 Y4.5235 -G1 X5.1671 Y4.5632 -G2 X5.1478 Y4.5797 I0.0955 J0.1315 -G0 Z0.25 -G0 X5.1965 Y4.6037 -G1 Z-0.05 F30 -G2 X5.1501 Y4.6947 I0.0661 J0.091 F10 -G2 X5.1506 Y4.7052 I0.1125 J0 -G2 X5.115 Y4.7225 I0.0304 J0.1083 -G1 X5.0309 Y4.7836 -G1 X4.9469 Y4.7225 -G2 X4.9112 Y4.7052 I-0.0661 J0.091 -G2 X4.9117 Y4.6947 I-0.112 J-0.0106 -G2 X4.8653 Y4.6037 I-0.1125 J0 -G1 X4.7813 Y4.5426 -G1 X4.8134 Y4.4439 -G2 X4.8189 Y4.4092 I-0.107 J-0.0347 -G2 X4.8187 Y4.4029 I-0.1125 J0 -G1 X4.8918 Y4.4029 -G1 X4.9238 Y4.5016 -G2 X5.1383 Y4.5001 I0.107 J-0.0347 -G1 X5.1684 Y4.4029 -G1 X5.2431 Y4.4029 -G2 X5.2429 Y4.4092 I0.1123 J0.0062 -G2 X5.2484 Y4.4439 I0.1125 J0 -G1 X5.2805 Y4.5426 -G1 X5.1965 Y4.6037 -G0 Z0.25 -G0 X4.9177 Y6.2007 -G1 Z-0.05 F30 -G2 X5.1457 Y6.199 I0.1132 J-0.1166 F10 -G2 X5.1017 Y6.2889 I0.1169 J0.1129 -G2 X5.0856 Y6.2992 I0.0793 J0.1418 -G1 X5.0309 Y6.339 -G1 X4.9763 Y6.2993 -G2 X4.96 Y6.2889 I-0.0955 J0.1315 -G2 X4.9177 Y6.2007 I-0.1609 J0.023 -G2 X4.9124 Y6.1953 I-0.1185 J0.1112 -G2 X4.9177 Y6.2007 I0.1185 J-0.1112 -G0 Z0.25 -G0 X5.1478 Y6.1969 -G1 Z-0.05 F30 -G2 X5.1861 Y6.1321 I-0.1169 J-0.1129 F10 -G1 X5.2021 Y6.0803 -G1 X5.2217 Y6.1407 -G1 X5.1671 Y6.1804 -G2 X5.1478 Y6.1969 I0.0955 J0.1315 -G0 Z0.25 -G0 X5.1965 Y6.2209 -G1 Z-0.05 F30 -G2 X5.1501 Y6.3119 I0.0661 J0.091 F10 -G2 X5.1506 Y6.3224 I0.1125 J0 -G2 X5.115 Y6.3397 I0.0304 J0.1083 -G1 X5.0309 Y6.4007 -G1 X4.9469 Y6.3397 -G2 X4.9112 Y6.3224 I-0.0661 J0.091 -G2 X4.9117 Y6.3119 I-0.112 J-0.0106 -G2 X4.8653 Y6.2209 I-0.1125 J0 -G1 X4.7813 Y6.1598 -G1 X4.8134 Y6.0611 -G2 X4.8189 Y6.0264 I-0.107 J-0.0347 -G2 X4.8187 Y6.0201 I-0.1125 J0 -G1 X4.8918 Y6.0201 -G1 X4.9238 Y6.1188 -G2 X5.1383 Y6.1173 I0.107 J-0.0347 -G1 X5.1684 Y6.0201 -G1 X5.2431 Y6.0201 -G2 X5.2429 Y6.0264 I0.1123 J0.0062 -G2 X5.2484 Y6.0611 I0.1125 J0 -G1 X5.2805 Y6.1598 -G1 X5.1965 Y6.2209 -G0 Z0.25 -G0 X4.4415 Y4.9862 -G1 Z-0.05 F30 -G2 X4.7115 Y4.9192 I0.1147 J-0.1151 F10 -G1 X4.7274 Y4.8676 -G1 X4.7471 Y4.928 -G1 X4.6925 Y4.9676 -G2 X4.6271 Y5.0768 I0.0955 J0.1315 -G2 X4.6108 Y5.0872 I0.0793 J0.1418 -G1 X4.5563 Y5.1268 -G1 X4.5017 Y5.0872 -G2 X4.4856 Y5.0769 I-0.0955 J0.1315 -G2 X4.4415 Y4.9862 I-0.161 J0.0222 -G2 X4.4393 Y4.984 I-0.1169 J0.1129 -G2 X4.4415 Y4.9862 I0.1169 J-0.1129 -G1 X4.3907 Y5.008 F10 -G1 X4.3067 Y4.947 F10 -G1 X4.3388 Y4.8483 -G2 X4.3443 Y4.8135 I-0.107 J-0.0347 -G2 X4.3441 Y4.8072 I-0.1125 J0 -G1 X4.4172 Y4.8072 -G1 X4.4493 Y4.9059 -G2 X4.6637 Y4.9044 I0.107 J-0.0347 -G1 X4.6938 Y4.8072 -G1 X4.7684 Y4.8072 -G2 X4.7682 Y4.8135 I0.1123 J0.0064 -G2 X4.7738 Y4.8483 I0.1125 J0 -G1 X4.8059 Y4.947 -G1 X4.7219 Y5.008 -G2 X4.6755 Y5.0991 I0.0661 J0.091 -G2 X4.6761 Y5.1103 I0.1125 J0 -G2 X4.6402 Y5.1276 I0.0303 J0.1084 -G1 X4.5563 Y5.1886 -G1 X4.4723 Y5.1276 -G2 X4.4365 Y5.1103 I-0.0661 J0.091 -G2 X4.4371 Y5.0991 I-0.1119 J-0.0113 -G2 X4.3907 Y5.008 I-0.1125 J0 -G0 Z0.25 -G0 X3.9668 Y4.5818 -G1 Z-0.05 F30 -G2 X4.1965 Y4.5818 I0.1148 J-0.115 F10 -G2 X4.1526 Y4.6716 I0.1169 J0.1129 -G2 X4.1363 Y4.6821 I0.0792 J0.1419 -G1 X4.0817 Y4.7217 -G1 X4.0271 Y4.6821 -G2 X4.0108 Y4.6716 I-0.0955 J0.1315 -G2 X3.9668 Y4.5818 I-0.1609 J0.023 -G2 X3.9648 Y4.5797 I-0.1169 J0.1129 -G2 X3.9668 Y4.5818 I0.1169 J-0.1129 -G0 Z0.25 -G0 X4.1986 Y4.5797 -G1 Z-0.05 F30 -G2 X4.2369 Y4.5149 I-0.1169 J-0.1129 F10 -G1 X4.2529 Y4.4633 -G1 X4.2725 Y4.5236 -G1 X4.2179 Y4.5632 -G2 X4.1986 Y4.5797 I0.0955 J0.1315 -G0 Z0.25 -G0 X4.2473 Y4.6037 -G1 Z-0.05 F30 -G2 X4.2009 Y4.6947 I0.0661 J0.091 F10 -G2 X4.2014 Y4.7052 I0.1125 J0 -G2 X4.1656 Y4.7225 I0.0303 J0.1083 -G1 X4.0817 Y4.7835 -G1 X3.9977 Y4.7225 -G2 X3.9619 Y4.7052 I-0.0661 J0.091 -G2 X3.9624 Y4.6947 I-0.112 J-0.0105 -G2 X3.916 Y4.6037 I-0.1125 J0 -G1 X3.8321 Y4.5427 -G1 X3.8642 Y4.444 -G2 X3.8697 Y4.4092 I-0.107 J-0.0348 -G2 X3.8695 Y4.4029 I-0.1125 J0 -G1 X3.9426 Y4.4029 -G1 X3.9747 Y4.5016 -G2 X4.1891 Y4.5001 I0.107 J-0.0347 -G1 X4.2192 Y4.4029 -G1 X4.2938 Y4.4029 -G2 X4.2937 Y4.4092 I0.1123 J0.0062 -G2 X4.2992 Y4.444 I0.1125 J0 -G1 X4.3313 Y4.5427 -G1 X4.2473 Y4.6037 -G0 Z0.25 -G0 X4.4431 Y4.1792 -G1 Z-0.05 F30 -G2 X4.6711 Y4.1776 I0.1132 J-0.1166 F10 -G2 X4.6272 Y4.2673 I0.1169 J0.1129 -G2 X4.6108 Y4.2777 I0.0792 J0.1419 -G1 X4.5563 Y4.3174 -G1 X4.5017 Y4.2777 -G2 X4.4854 Y4.2673 I-0.0955 J0.1315 -G2 X4.4431 Y4.1792 I-0.1609 J0.0231 -G2 X4.4378 Y4.1738 I-0.1185 J0.1112 -G2 X4.4431 Y4.1792 I0.1185 J-0.1112 -G0 Z0.25 -G0 X4.6732 Y4.1755 -G1 Z-0.05 F30 -G2 X4.7115 Y4.1106 I-0.1169 J-0.1129 F10 -G1 X4.7275 Y4.059 -G1 X4.7471 Y4.1193 -G1 X4.6925 Y4.159 -G2 X4.6732 Y4.1755 I0.0955 J0.1315 -G0 Z0.25 -G0 X4.7219 Y4.1994 -G1 Z-0.05 F30 -G2 X4.6755 Y4.2904 I0.0661 J0.091 F10 -G2 X4.676 Y4.3008 I0.1125 J0 -G2 X4.6402 Y4.3182 I0.0303 J0.1083 -G1 X4.5563 Y4.3792 -G1 X4.4723 Y4.3182 -G2 X4.4366 Y4.3009 I-0.0661 J0.091 -G2 X4.4371 Y4.2904 I-0.112 J-0.0104 -G2 X4.3907 Y4.1994 I-0.1125 J0 -G1 X4.3067 Y4.1384 -G1 X4.3388 Y4.0396 -G2 X4.3443 Y4.0049 I-0.107 J-0.0347 -G2 X4.3441 Y3.9986 I-0.1125 J0 -G1 X4.4172 Y3.9986 -G1 X4.4493 Y4.0973 -G2 X4.6637 Y4.0958 I0.107 J-0.0347 -G1 X4.6938 Y3.9986 -G1 X4.7684 Y3.9986 -G2 X4.7682 Y4.0049 I0.1123 J0.0062 -G2 X4.7738 Y4.0397 I0.1125 J0 -G1 X4.8059 Y4.1384 -G1 X4.7219 Y4.1994 -G0 Z0.25 -G0 X4.4415 Y6.6034 -G1 Z-0.05 F30 -G2 X4.7115 Y6.5364 I0.1147 J-0.1151 F10 -G1 X4.7274 Y6.4848 -G1 X4.7471 Y6.5451 -G1 X4.6925 Y6.5848 -G2 X4.6271 Y6.694 I0.0955 J0.1315 -G2 X4.6108 Y6.7044 I0.0793 J0.1418 -G1 X4.5563 Y6.744 -G1 X4.5017 Y6.7044 -G2 X4.4856 Y6.6941 I-0.0955 J0.1315 -G2 X4.4415 Y6.6034 I-0.161 J0.0222 -G2 X4.4393 Y6.6012 I-0.1169 J0.1129 -G2 X4.4415 Y6.6034 I0.1169 J-0.1129 -G1 X4.3907 Y6.6252 F10 -G1 X4.3067 Y6.5642 F10 -G1 X4.3388 Y6.4655 -G2 X4.3443 Y6.4307 I-0.107 J-0.0347 -G2 X4.3441 Y6.4244 I-0.1125 J0 -G1 X4.4172 Y6.4244 -G1 X4.4493 Y6.5231 -G2 X4.6637 Y6.5216 I0.107 J-0.0347 -G1 X4.6938 Y6.4244 -G1 X4.7684 Y6.4244 -G2 X4.7682 Y6.4307 I0.1123 J0.0064 -G2 X4.7738 Y6.4655 I0.1125 J0 -G1 X4.8059 Y6.5642 -G1 X4.7219 Y6.6252 -G2 X4.6755 Y6.7162 I0.0661 J0.091 -G2 X4.6761 Y6.7275 I0.1125 J0 -G2 X4.6402 Y6.7448 I0.0303 J0.1084 -G1 X4.5563 Y6.8058 -G1 X4.4723 Y6.7448 -G2 X4.4365 Y6.7275 I-0.0661 J0.091 -G2 X4.4371 Y6.7162 I-0.1119 J-0.0113 -G2 X4.3907 Y6.6252 I-0.1125 J0 -G0 Z0.25 -G0 X2.9778 Y5.3257 -G1 Z-0.05 F30 -G2 X3.2876 Y5.3235 I0.1546 J-0.0502 F10 -G1 X3.3035 Y5.2722 -G1 X3.3233 Y5.333 -G1 X3.2687 Y5.3727 -G2 X3.2035 Y5.4802 I0.0955 J0.1315 -G2 X3.1871 Y5.4906 I0.0792 J0.1419 -G1 X3.1324 Y5.5303 -G1 X3.0778 Y5.4906 -G2 X3.0615 Y5.4802 I-0.0955 J0.1315 -G2 X2.9963 Y5.3727 I-0.1607 J0.024 -G1 X2.9416 Y5.333 -G1 X2.9609 Y5.2736 -G1 X2.9778 Y5.3257 -G1 X3.0254 Y5.3103 F10 -G2 X3.2399 Y5.3088 I0.107 J-0.0347 F10 -G1 X3.2699 Y5.2116 -G1 X3.3447 Y5.2116 -G2 X3.3445 Y5.2186 I0.1123 J0.0071 -G2 X3.35 Y5.2534 I0.1125 J0 -G1 X3.382 Y5.3521 -G1 X3.298 Y5.4132 -G2 X3.2517 Y5.5042 I0.0661 J0.091 -G2 X3.2521 Y5.5138 I0.1125 J0 -G2 X3.2165 Y5.531 I0.0305 J0.1083 -G1 X3.1324 Y5.5921 -G1 X3.0484 Y5.5311 -G2 X3.0128 Y5.5138 I-0.0661 J0.091 -G2 X3.0132 Y5.5042 I-0.1121 J-0.0096 -G2 X2.9669 Y5.4132 I-0.1125 J0 -G1 X2.8829 Y5.3521 -G1 X2.9149 Y5.2534 -G2 X2.9204 Y5.2186 I-0.107 J-0.0347 -G2 X2.9202 Y5.2116 I-0.1125 J0 -G1 X2.9934 Y5.2116 -G1 X3.0254 Y5.3103 -G0 Z0.25 -G0 X2.5431 Y6.6034 -G1 Z-0.05 F30 -G2 X2.8131 Y6.5364 I0.1147 J-0.1151 F10 -G1 X2.829 Y6.4848 -G1 X2.8486 Y6.5451 -G1 X2.7941 Y6.5848 -G2 X2.7286 Y6.694 I0.0955 J0.1315 -G2 X2.7124 Y6.7044 I0.0793 J0.1418 -G1 X2.6578 Y6.744 -G1 X2.6032 Y6.7044 -G2 X2.5871 Y6.6941 I-0.0955 J0.1315 -G2 X2.5431 Y6.6034 I-0.161 J0.0222 -G2 X2.5409 Y6.6012 I-0.1169 J0.1129 -G2 X2.5431 Y6.6034 I0.1169 J-0.1129 -G1 X2.4923 Y6.6252 F10 -G1 X2.4083 Y6.5642 F10 -G1 X2.4403 Y6.4655 -G2 X2.4458 Y6.4307 I-0.107 J-0.0347 -G2 X2.4457 Y6.4244 I-0.1125 J0 -G1 X2.5188 Y6.4244 -G1 X2.5508 Y6.5231 -G2 X2.7653 Y6.5216 I0.107 J-0.0347 -G1 X2.7954 Y6.4244 -G1 X2.87 Y6.4244 -G2 X2.8698 Y6.4307 I0.1123 J0.0064 -G2 X2.8753 Y6.4655 I0.1125 J0 -G1 X2.9074 Y6.5642 -G1 X2.8235 Y6.6252 -G2 X2.7771 Y6.7162 I0.0661 J0.091 -G2 X2.7777 Y6.7275 I0.1125 J0 -G2 X2.7418 Y6.7448 I0.0303 J0.1084 -G1 X2.6578 Y6.8058 -G1 X2.5738 Y6.7448 -G2 X2.5381 Y6.7275 I-0.0661 J0.091 -G2 X2.5387 Y6.7162 I-0.1119 J-0.0113 -G2 X2.4923 Y6.6252 I-0.1125 J0 -G0 Z0.25 -G0 X2.0684 Y6.199 -G1 Z-0.05 F30 -G2 X2.2981 Y6.199 I0.1148 J-0.115 F10 -G2 X2.2541 Y6.2888 I0.1169 J0.1129 -G2 X2.2378 Y6.2993 I0.0792 J0.1419 -G1 X2.1832 Y6.3389 -G1 X2.1286 Y6.2993 -G2 X2.1123 Y6.2888 I-0.0955 J0.1315 -G2 X2.0684 Y6.199 I-0.1609 J0.023 -G2 X2.0663 Y6.1969 I-0.1169 J0.1129 -G2 X2.0684 Y6.199 I0.1169 J-0.1129 -G0 Z0.25 -G0 X2.3002 Y6.1969 -G1 Z-0.05 F30 -G2 X2.3385 Y6.1321 I-0.1169 J-0.1129 F10 -G1 X2.3544 Y6.0805 -G1 X2.3741 Y6.1408 -G1 X2.3195 Y6.1804 -G2 X2.3002 Y6.1969 I0.0955 J0.1315 -G0 Z0.25 -G0 X2.3489 Y6.2209 -G1 Z-0.05 F30 -G2 X2.3025 Y6.3119 I0.0661 J0.091 F10 -G2 X2.303 Y6.3224 I0.1125 J0 -G2 X2.2672 Y6.3397 I0.0303 J0.1083 -G1 X2.1832 Y6.4007 -G1 X2.0993 Y6.3397 -G2 X2.0635 Y6.3224 I-0.0661 J0.091 -G2 X2.064 Y6.3119 I-0.112 J-0.0105 -G2 X2.0176 Y6.2209 I-0.1125 J0 -G1 X1.9336 Y6.1599 -G1 X1.9657 Y6.0612 -G2 X1.9713 Y6.0264 I-0.107 J-0.0348 -G2 X1.9711 Y6.0201 I-0.1125 J0 -G1 X2.0442 Y6.0201 -G1 X2.0762 Y6.1188 -G2 X2.2907 Y6.1173 I0.107 J-0.0347 -G1 X2.3208 Y6.0201 -G1 X2.3954 Y6.0201 -G2 X2.3952 Y6.0264 I0.1123 J0.0062 -G2 X2.4007 Y6.0612 I0.1125 J0 -G1 X2.4328 Y6.1599 -G1 X2.3489 Y6.2209 -G0 Z0.25 -G0 X2.0287 Y5.3257 -G1 Z-0.05 F30 -G2 X2.3385 Y5.3235 I0.1546 J-0.0502 F10 -G1 X2.3543 Y5.2724 -G1 X2.3741 Y5.3331 -G1 X2.3195 Y5.3727 -G2 X2.2543 Y5.4801 I0.0955 J0.1315 -G2 X2.2378 Y5.4906 I0.079 J0.142 -G1 X2.1832 Y5.5303 -G1 X2.1286 Y5.4906 -G2 X2.1122 Y5.4801 I-0.0955 J0.1315 -G2 X2.047 Y5.3727 I-0.1607 J0.0241 -G1 X1.9924 Y5.3331 -G1 X2.0118 Y5.2736 -G1 X2.0287 Y5.3257 -G1 X2.0762 Y5.3103 F10 -G2 X2.2907 Y5.3088 I0.107 J-0.0347 F10 -G1 X2.3208 Y5.2116 -G1 X2.3954 Y5.2116 -G2 X2.3952 Y5.2186 I0.1123 J0.0071 -G2 X2.4007 Y5.2534 I0.1125 J0 -G1 X2.4328 Y5.3521 -G1 X2.3489 Y5.4132 -G2 X2.3025 Y5.5042 I0.0661 J0.091 -G2 X2.3029 Y5.5138 I0.1125 J0 -G2 X2.2672 Y5.5311 I0.0304 J0.1083 -G1 X2.1832 Y5.5921 -G1 X2.0993 Y5.5311 -G2 X2.0636 Y5.5138 I-0.0661 J0.091 -G2 X2.064 Y5.5042 I-0.1121 J-0.0096 -G2 X2.0176 Y5.4132 I-0.1125 J0 -G1 X1.9336 Y5.3521 -G1 X1.9657 Y5.2534 -G2 X1.9713 Y5.2186 I-0.107 J-0.0348 -G2 X1.971 Y5.2116 I-0.1125 J0 -G1 X2.0442 Y5.2116 -G1 X2.0762 Y5.3103 -G0 Z0.25 -G0 X4.8763 Y5.3257 -G1 Z-0.05 F30 -G2 X5.1861 Y5.3235 I0.1546 J-0.0502 F10 -G1 X5.202 Y5.2722 -G1 X5.2217 Y5.333 -G1 X5.1671 Y5.3727 -G2 X5.1019 Y5.4802 I0.0955 J0.1315 -G2 X5.0856 Y5.4906 I0.0792 J0.1419 -G1 X5.0309 Y5.5303 -G1 X4.9763 Y5.4906 -G2 X4.9599 Y5.4802 I-0.0955 J0.1315 -G2 X4.8947 Y5.3727 I-0.1607 J0.024 -G1 X4.8401 Y5.333 -G1 X4.8594 Y5.2736 -G1 X4.8763 Y5.3257 -G1 X4.9238 Y5.3103 F10 -G2 X5.1383 Y5.3088 I0.107 J-0.0347 F10 -G1 X5.1684 Y5.2116 -G1 X5.2431 Y5.2116 -G2 X5.2429 Y5.2186 I0.1123 J0.0071 -G2 X5.2484 Y5.2534 I0.1125 J0 -G1 X5.2805 Y5.3521 -G1 X5.1965 Y5.4132 -G2 X5.1501 Y5.5042 I0.0661 J0.091 -G2 X5.1505 Y5.5138 I0.1125 J0 -G2 X5.115 Y5.531 I0.0305 J0.1083 -G1 X5.0309 Y5.5921 -G1 X4.9469 Y5.5311 -G2 X4.9113 Y5.5138 I-0.0661 J0.091 -G2 X4.9117 Y5.5042 I-0.1121 J-0.0096 -G2 X4.8653 Y5.4132 I-0.1125 J0 -G1 X4.7813 Y5.3521 -G1 X4.8134 Y5.2534 -G2 X4.8189 Y5.2186 I-0.107 J-0.0347 -G2 X4.8186 Y5.2116 I-0.1125 J0 -G1 X4.8918 Y5.2116 -G1 X4.9238 Y5.3103 -G0 Z0.25 -G0 X2.5446 Y4.1792 -G1 Z-0.05 F30 -G2 X2.7727 Y4.1776 I0.1132 J-0.1166 F10 -G2 X2.7287 Y4.2673 I0.1169 J0.1129 -G2 X2.7124 Y4.2777 I0.0792 J0.1419 -G1 X2.6578 Y4.3174 -G1 X2.6032 Y4.2777 -G2 X2.587 Y4.2673 I-0.0955 J0.1315 -G2 X2.5446 Y4.1792 I-0.1609 J0.0231 -G2 X2.5393 Y4.1738 I-0.1185 J0.1112 -G2 X2.5446 Y4.1792 I0.1185 J-0.1112 -G0 Z0.25 -G0 X2.7747 Y4.1755 -G1 Z-0.05 F30 -G2 X2.8131 Y4.1106 I-0.1169 J-0.1129 F10 -G1 X2.829 Y4.059 -G1 X2.8486 Y4.1193 -G1 X2.7941 Y4.159 -G2 X2.7747 Y4.1755 I0.0955 J0.1315 -G0 Z0.25 -G0 X2.8235 Y4.1994 -G1 Z-0.05 F30 -G2 X2.7771 Y4.2904 I0.0661 J0.091 F10 -G2 X2.7776 Y4.3008 I0.1125 J0 -G2 X2.7418 Y4.3182 I0.0303 J0.1083 -G1 X2.6578 Y4.3792 -G1 X2.5738 Y4.3182 -G2 X2.5382 Y4.3009 I-0.0661 J0.091 -G2 X2.5387 Y4.2904 I-0.112 J-0.0104 -G2 X2.4923 Y4.1994 I-0.1125 J0 -G1 X2.4083 Y4.1384 -G1 X2.4403 Y4.0396 -G2 X2.4458 Y4.0049 I-0.107 J-0.0347 -G2 X2.4457 Y3.9986 I-0.1125 J0 -G1 X2.5188 Y3.9986 -G1 X2.5508 Y4.0973 -G2 X2.7653 Y4.0958 I0.107 J-0.0347 -G1 X2.7954 Y3.9986 -G1 X2.87 Y3.9986 -G2 X2.8698 Y4.0049 I0.1123 J0.0062 -G2 X2.8753 Y4.0397 I0.1125 J0 -G1 X2.9074 Y4.1384 -G1 X2.8235 Y4.1994 -G0 Z0.25 -G0 X2.0684 Y4.5818 -G1 Z-0.05 F30 -G2 X2.2981 Y4.5818 I0.1148 J-0.115 F10 -G2 X2.2541 Y4.6716 I0.1169 J0.1129 -G2 X2.2378 Y4.6821 I0.0792 J0.1419 -G1 X2.1832 Y4.7217 -G1 X2.1286 Y4.6821 -G2 X2.1123 Y4.6716 I-0.0955 J0.1315 -G2 X2.0684 Y4.5818 I-0.1609 J0.023 -G2 X2.0663 Y4.5797 I-0.1169 J0.1129 -G2 X2.0684 Y4.5818 I0.1169 J-0.1129 -G0 Z0.25 -G0 X2.3002 Y4.5797 -G1 Z-0.05 F30 -G2 X2.3385 Y4.5149 I-0.1169 J-0.1129 F10 -G1 X2.3544 Y4.4633 -G1 X2.3741 Y4.5236 -G1 X2.3195 Y4.5632 -G2 X2.3002 Y4.5797 I0.0955 J0.1315 -G0 Z0.25 -G0 X2.3489 Y4.6037 -G1 Z-0.05 F30 -G2 X2.3025 Y4.6947 I0.0661 J0.091 F10 -G2 X2.303 Y4.7052 I0.1125 J0 -G2 X2.2672 Y4.7225 I0.0303 J0.1083 -G1 X2.1832 Y4.7835 -G1 X2.0993 Y4.7225 -G2 X2.0635 Y4.7052 I-0.0661 J0.091 -G2 X2.064 Y4.6947 I-0.112 J-0.0105 -G2 X2.0176 Y4.6037 I-0.1125 J0 -G1 X1.9336 Y4.5427 -G1 X1.9657 Y4.444 -G2 X1.9713 Y4.4092 I-0.107 J-0.0348 -G2 X1.9711 Y4.4029 I-0.1125 J0 -G1 X2.0442 Y4.4029 -G1 X2.0762 Y4.5016 -G2 X2.2907 Y4.5001 I0.107 J-0.0347 -G1 X2.3208 Y4.4029 -G1 X2.3954 Y4.4029 -G2 X2.3952 Y4.4092 I0.1123 J0.0062 -G2 X2.4007 Y4.444 I0.1125 J0 -G1 X2.4328 Y4.5427 -G1 X2.3489 Y4.6037 -G0 Z0.25 -G0 X2.5431 Y4.9862 -G1 Z-0.05 F30 -G2 X2.8131 Y4.9192 I0.1147 J-0.1151 F10 -G1 X2.829 Y4.8676 -G1 X2.8486 Y4.928 -G1 X2.7941 Y4.9676 -G2 X2.7286 Y5.0768 I0.0955 J0.1315 -G2 X2.7124 Y5.0872 I0.0793 J0.1418 -G1 X2.6578 Y5.1268 -G1 X2.6032 Y5.0872 -G2 X2.5871 Y5.0769 I-0.0955 J0.1315 -G2 X2.5431 Y4.9862 I-0.161 J0.0222 -G2 X2.5409 Y4.984 I-0.1169 J0.1129 -G2 X2.5431 Y4.9862 I0.1169 J-0.1129 -G1 X2.4923 Y5.008 F10 -G1 X2.4083 Y4.947 F10 -G1 X2.4403 Y4.8483 -G2 X2.4458 Y4.8135 I-0.107 J-0.0347 -G2 X2.4457 Y4.8072 I-0.1125 J0 -G1 X2.5188 Y4.8072 -G1 X2.5508 Y4.9059 -G2 X2.7653 Y4.9044 I0.107 J-0.0347 -G1 X2.7954 Y4.8072 -G1 X2.87 Y4.8072 -G2 X2.8698 Y4.8135 I0.1123 J0.0064 -G2 X2.8753 Y4.8483 I0.1125 J0 -G1 X2.9074 Y4.947 -G1 X2.8235 Y5.008 -G2 X2.7771 Y5.0991 I0.0661 J0.091 -G2 X2.7777 Y5.1103 I0.1125 J0 -G2 X2.7418 Y5.1276 I0.0303 J0.1084 -G1 X2.6578 Y5.1886 -G1 X2.5738 Y5.1276 -G2 X2.5381 Y5.1103 I-0.0661 J0.091 -G2 X2.5387 Y5.0991 I-0.1119 J-0.0113 -G2 X2.4923 Y5.008 I-0.1125 J0 -G0 Z0.25 -G0 X1.0794 Y5.3257 -G1 Z-0.05 F30 -G2 X1.3892 Y5.3235 I0.1546 J-0.0502 F10 -G1 X1.4051 Y5.2722 -G1 X1.4248 Y5.333 -G1 X1.3702 Y5.3727 -G2 X1.305 Y5.4802 I0.0955 J0.1315 -G2 X1.2887 Y5.4906 I0.0792 J0.1419 -G1 X1.234 Y5.5303 -G1 X1.1793 Y5.4906 -G2 X1.163 Y5.4802 I-0.0955 J0.1315 -G2 X1.0978 Y5.3727 I-0.1607 J0.024 -G1 X1.0432 Y5.333 -G1 X1.0625 Y5.2736 -G1 X1.0794 Y5.3257 -G1 X1.127 Y5.3103 F10 -G2 X1.3414 Y5.3088 I0.107 J-0.0347 F10 -G1 X1.3715 Y5.2116 -G1 X1.4463 Y5.2116 -G2 X1.446 Y5.2186 I0.1123 J0.0071 -G2 X1.4515 Y5.2534 I0.1125 J0 -G1 X1.4836 Y5.3521 -G1 X1.3996 Y5.4132 -G2 X1.3532 Y5.5042 I0.0661 J0.091 -G2 X1.3536 Y5.5138 I0.1125 J0 -G2 X1.318 Y5.5311 I0.0305 J0.1083 -G1 X1.234 Y5.5921 -G1 X1.15 Y5.531 -G2 X1.1144 Y5.5138 I-0.0661 J0.091 -G2 X1.1148 Y5.5042 I-0.1121 J-0.0096 -G2 X1.0684 Y5.4132 I-0.1125 J0 -G1 X0.9844 Y5.3521 -G1 X1.0165 Y5.2534 -G2 X1.022 Y5.2186 I-0.107 J-0.0347 -G2 X1.0218 Y5.2116 I-0.1125 J0 -G1 X1.0949 Y5.2116 -G1 X1.127 Y5.3103 -G0 Z0.25 -G0 X3.9668 Y6.199 -G1 Z-0.05 F30 -G2 X4.1965 Y6.199 I0.1148 J-0.115 F10 -G2 X4.1526 Y6.2888 I0.1169 J0.1129 -G2 X4.1363 Y6.2993 I0.0792 J0.1419 -G1 X4.0817 Y6.3389 -G1 X4.0271 Y6.2993 -G2 X4.0108 Y6.2888 I-0.0955 J0.1315 -G2 X3.9668 Y6.199 I-0.1609 J0.023 -G2 X3.9648 Y6.1969 I-0.1169 J0.1129 -G2 X3.9668 Y6.199 I0.1169 J-0.1129 -G0 Z0.25 -G0 X4.1986 Y6.1969 -G1 Z-0.05 F30 -G2 X4.2369 Y6.1321 I-0.1169 J-0.1129 F10 -G1 X4.2529 Y6.0805 -G1 X4.2725 Y6.1408 -G1 X4.2179 Y6.1804 -G2 X4.1986 Y6.1969 I0.0955 J0.1315 -G0 Z0.25 -G0 X4.2473 Y6.2209 -G1 Z-0.05 F30 -G2 X4.2009 Y6.3119 I0.0661 J0.091 F10 -G2 X4.2014 Y6.3224 I0.1125 J0 -G2 X4.1656 Y6.3397 I0.0303 J0.1083 -G1 X4.0817 Y6.4007 -G1 X3.9977 Y6.3397 -G2 X3.9619 Y6.3224 I-0.0661 J0.091 -G2 X3.9624 Y6.3119 I-0.112 J-0.0105 -G2 X3.916 Y6.2209 I-0.1125 J0 -G1 X3.8321 Y6.1599 -G1 X3.8642 Y6.0612 -G2 X3.8697 Y6.0264 I-0.107 J-0.0348 -G2 X3.8695 Y6.0201 I-0.1125 J0 -G1 X3.9426 Y6.0201 -G1 X3.9747 Y6.1188 -G2 X4.1891 Y6.1173 I0.107 J-0.0347 -G1 X4.2192 Y6.0201 -G1 X4.2938 Y6.0201 -G2 X4.2937 Y6.0264 I0.1123 J0.0062 -G2 X4.2992 Y6.0612 I0.1125 J0 -G1 X4.3313 Y6.1599 -G1 X4.2473 Y6.2209 -G0 Z0.25 -G0 X3.0192 Y4.5835 -G1 Z-0.05 F30 -G2 X3.2473 Y4.5818 I0.1132 J-0.1166 F10 -G2 X3.2033 Y4.6717 I0.1169 J0.1129 -G2 X3.1871 Y4.682 I0.0793 J0.1418 -G1 X3.1324 Y4.7218 -G1 X3.0778 Y4.6821 -G2 X3.0616 Y4.6717 I-0.0955 J0.1315 -G2 X3.0192 Y4.5835 I-0.1609 J0.023 -G2 X3.0139 Y4.5781 I-0.1185 J0.1112 -G2 X3.0192 Y4.5835 I0.1185 J-0.1112 -G0 Z0.25 -G0 X3.2493 Y4.5797 -G1 Z-0.05 F30 -G2 X3.2876 Y4.5149 I-0.1169 J-0.1129 F10 -G1 X3.3037 Y4.4631 -G1 X3.3233 Y4.5235 -G1 X3.2687 Y4.5632 -G2 X3.2493 Y4.5797 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.298 Y4.6037 -G1 Z-0.05 F30 -G2 X3.2517 Y4.6947 I0.0661 J0.091 F10 -G2 X3.2522 Y4.7052 I0.1125 J0 -G2 X3.2165 Y4.7225 I0.0304 J0.1083 -G1 X3.1324 Y4.7836 -G1 X3.0484 Y4.7225 -G2 X3.0127 Y4.7052 I-0.0661 J0.091 -G2 X3.0132 Y4.6947 I-0.112 J-0.0106 -G2 X2.9669 Y4.6037 I-0.1125 J0 -G1 X2.8829 Y4.5426 -G1 X2.9149 Y4.4439 -G2 X2.9204 Y4.4092 I-0.107 J-0.0347 -G2 X2.9202 Y4.4029 I-0.1125 J0 -G1 X2.9934 Y4.4029 -G1 X3.0254 Y4.5016 -G2 X3.2399 Y4.5001 I0.107 J-0.0347 -G1 X3.2699 Y4.4029 -G1 X3.3447 Y4.4029 -G2 X3.3445 Y4.4092 I0.1123 J0.0062 -G2 X3.35 Y4.4439 I0.1125 J0 -G1 X3.382 Y4.5426 -G1 X3.298 Y4.6037 -G0 Z0.25 -G0 X3.9271 Y5.3257 -G1 Z-0.05 F30 -G2 X4.2369 Y5.3235 I0.1546 J-0.0502 F10 -G1 X4.2527 Y5.2724 -G1 X4.2725 Y5.3331 -G1 X4.2179 Y5.3727 -G2 X4.1527 Y5.4801 I0.0955 J0.1315 -G2 X4.1363 Y5.4906 I0.079 J0.142 -G1 X4.0817 Y5.5303 -G1 X4.0271 Y5.4906 -G2 X4.0106 Y5.4801 I-0.0955 J0.1315 -G2 X3.9454 Y5.3727 I-0.1607 J0.0241 -G1 X3.8909 Y5.3331 -G1 X3.9102 Y5.2736 -G1 X3.9271 Y5.3257 -G1 X3.9747 Y5.3103 F10 -G2 X4.1891 Y5.3088 I0.107 J-0.0347 F10 -G1 X4.2192 Y5.2116 -G1 X4.2939 Y5.2116 -G2 X4.2937 Y5.2186 I0.1123 J0.0071 -G2 X4.2992 Y5.2534 I0.1125 J0 -G1 X4.3313 Y5.3521 -G1 X4.2473 Y5.4132 -G2 X4.2009 Y5.5042 I0.0661 J0.091 -G2 X4.2014 Y5.5138 I0.1125 J0 -G2 X4.1656 Y5.5311 I0.0304 J0.1083 -G1 X4.0817 Y5.5921 -G1 X3.9977 Y5.5311 -G2 X3.962 Y5.5138 I-0.0661 J0.091 -G2 X3.9624 Y5.5042 I-0.1121 J-0.0096 -G2 X3.916 Y5.4132 I-0.1125 J0 -G1 X3.8321 Y5.3521 -G1 X3.8642 Y5.2534 -G2 X3.8697 Y5.2186 I-0.107 J-0.0348 -G2 X3.8695 Y5.2116 I-0.1125 J0 -G1 X3.9426 Y5.2116 -G1 X3.9747 Y5.3103 -G0 Z0.25 -G0 X3.0192 Y6.2007 -G1 Z-0.05 F30 -G2 X3.2473 Y6.199 I0.1132 J-0.1166 F10 -G2 X3.2033 Y6.2889 I0.1169 J0.1129 -G2 X3.1871 Y6.2992 I0.0793 J0.1418 -G1 X3.1324 Y6.339 -G1 X3.0778 Y6.2993 -G2 X3.0616 Y6.2889 I-0.0955 J0.1315 -G2 X3.0192 Y6.2007 I-0.1609 J0.023 -G2 X3.0139 Y6.1953 I-0.1185 J0.1112 -G2 X3.0192 Y6.2007 I0.1185 J-0.1112 -G0 Z0.25 -G0 X3.2493 Y6.1969 -G1 Z-0.05 F30 -G2 X3.2876 Y6.1321 I-0.1169 J-0.1129 F10 -G1 X3.3037 Y6.0803 -G1 X3.3233 Y6.1407 -G1 X3.2687 Y6.1804 -G2 X3.2493 Y6.1969 I0.0955 J0.1315 -G0 Z0.25 -G0 X3.298 Y6.2209 -G1 Z-0.05 F30 -G2 X3.2517 Y6.3119 I0.0661 J0.091 F10 -G2 X3.2522 Y6.3224 I0.1125 J0 -G2 X3.2165 Y6.3397 I0.0304 J0.1083 -G1 X3.1324 Y6.4007 -G1 X3.0484 Y6.3397 -G2 X3.0127 Y6.3224 I-0.0661 J0.091 -G2 X3.0132 Y6.3119 I-0.112 J-0.0106 -G2 X2.9669 Y6.2209 I-0.1125 J0 -G1 X2.8829 Y6.1598 -G1 X2.9149 Y6.0611 -G2 X2.9204 Y6.0264 I-0.107 J-0.0347 -G2 X2.9202 Y6.0201 I-0.1125 J0 -G1 X2.9934 Y6.0201 -G1 X3.0254 Y6.1188 -G2 X3.2399 Y6.1173 I0.107 J-0.0347 -G1 X3.2699 Y6.0201 -G1 X3.3447 Y6.0201 -G2 X3.3445 Y6.0264 I0.1123 J0.0062 -G2 X3.35 Y6.0611 I0.1125 J0 -G1 X3.382 Y6.1598 -G1 X3.298 Y6.2209 -G0 Z0.25 -G0 X5.7739 Y7.2674 -G1 Z-0.05 F30 -G1 X5.6327 Y7.2674 F10 -G1 X5.643 Y7.2339 -G1 X5.7483 Y7.2339 -G2 X5.7739 Y7.2309 I0 J-0.1125 -G1 X5.7739 Y7.2674 -G0 Z0.25 -G0 X0.6312 Y7.2674 -G1 Z-0.05 F30 -G1 X0.491 Y7.2674 F10 -G1 X0.491 Y7.2309 -G2 X0.5166 Y7.2339 I0.0255 J-0.1096 -G1 X0.6203 Y7.2339 -G1 X0.6312 Y7.2674 -G0 Z0.25 -G0 X0.491 Y3.7656 -G1 Z-0.05 F30 -G1 X0.491 Y3.6486 F10 -G1 X0.5066 Y3.6486 -G1 X0.5344 Y3.7341 -G1 X0.491 Y3.7656 -G0 Z0.25 -G0 X5.7739 Y3.6486 -G1 Z-0.05 F30 -G1 X5.7739 Y3.7656 F10 -G1 X5.7305 Y3.7341 -G1 X5.7583 Y3.6486 -G1 X5.7739 Y3.6486 -G0 Z0.25 -G0 X5.7151 Y3.62 -G1 Z-0.05 F30 -G2 X5.7181 Y3.6006 I-0.0594 J-0.0193 F10 -G2 X5.7181 Y3.5986 I-0.0625 J0 -G1 X5.8239 Y3.5986 -G1 X5.8239 Y7.3174 -G1 X5.5649 Y7.3174 -G2 X5.5652 Y7.3163 I-0.0594 J-0.0195 -G1 X5.6061 Y7.1839 -G1 X5.7483 Y7.1839 -G2 X5.8108 Y7.1214 I0 J-0.0625 -G2 X5.7851 Y7.0708 I-0.0625 J0 -G1 X5.6717 Y6.9884 -G1 X5.7151 Y6.8552 -G2 X5.7181 Y6.8358 I-0.0594 J-0.0193 -G2 X5.6189 Y6.7853 I-0.0625 J0 -G1 X5.5055 Y6.8676 -G1 X5.3922 Y6.7853 -G2 X5.2929 Y6.8358 I-0.0367 J0.0506 -G2 X5.296 Y6.8551 I0.0625 J0 -G1 X5.3393 Y6.9884 -G1 X5.2259 Y7.0708 -G2 X5.2001 Y7.1214 I0.0367 J0.0506 -G2 X5.2626 Y7.1839 I0.0625 J0 -G1 X5.4027 Y7.1839 -G1 X5.4461 Y7.3172 -G1 X5.4461 Y7.3174 -G1 X4.6156 Y7.3174 -G2 X4.616 Y7.3164 I-0.0594 J-0.0195 -G1 X4.6569 Y7.1839 -G1 X4.7992 Y7.1839 -G2 X4.8617 Y7.1214 I0 J-0.0625 -G2 X4.8359 Y7.0708 I-0.0625 J0 -G1 X4.7225 Y6.9884 -G1 X4.7658 Y6.8551 -G2 X4.7689 Y6.8358 I-0.0594 J-0.0193 -G2 X4.6696 Y6.7853 I-0.0625 J0 -G1 X4.5563 Y6.8676 -G1 X4.4429 Y6.7853 -G2 X4.3437 Y6.8358 I-0.0367 J0.0506 -G2 X4.3467 Y6.8552 I0.0625 J0 -G1 X4.3901 Y6.9884 -G1 X4.2767 Y7.0708 -G2 X4.2509 Y7.1214 I0.0367 J0.0506 -G2 X4.3134 Y7.1839 I0.0625 J0 -G1 X4.4535 Y7.1839 -G1 X4.4968 Y7.3172 -G1 X4.4969 Y7.3174 -G1 X3.6665 Y7.3174 -G2 X3.6668 Y7.3163 I-0.0594 J-0.0195 -G1 X3.7077 Y7.1839 -G1 X3.8499 Y7.1839 -G2 X3.9124 Y7.1214 I0 J-0.0625 -G2 X3.8866 Y7.0708 I-0.0625 J0 -G1 X3.7733 Y6.9884 -G1 X3.8166 Y6.8552 -G2 X3.8197 Y6.8358 I-0.0594 J-0.0193 -G2 X3.7205 Y6.7853 I-0.0625 J0 -G1 X3.6071 Y6.8676 -G1 X3.4937 Y6.7853 -G2 X3.3945 Y6.8358 I-0.0367 J0.0506 -G2 X3.3975 Y6.8551 I0.0625 J0 -G1 X3.4408 Y6.9884 -G1 X3.3274 Y7.0708 -G2 X3.3017 Y7.1214 I0.0367 J0.0506 -G2 X3.3642 Y7.1839 I0.0625 J0 -G1 X3.5043 Y7.1839 -G1 X3.5477 Y7.3172 -G1 X3.5477 Y7.3174 -G1 X2.7172 Y7.3174 -G2 X2.7175 Y7.3164 I-0.0594 J-0.0195 -G1 X2.7585 Y7.1839 -G1 X2.9007 Y7.1839 -G2 X2.9632 Y7.1214 I0 J-0.0625 -G2 X2.9375 Y7.0708 I-0.0625 J0 -G1 X2.8241 Y6.9884 -G1 X2.8674 Y6.8551 -G2 X2.8704 Y6.8358 I-0.0594 J-0.0193 -G2 X2.7712 Y6.7853 I-0.0625 J0 -G1 X2.6578 Y6.8676 -G1 X2.5445 Y6.7853 -G2 X2.4452 Y6.8358 I-0.0367 J0.0506 -G2 X2.4483 Y6.8552 I0.0625 J0 -G1 X2.4916 Y6.9884 -G1 X2.3783 Y7.0708 -G2 X2.3525 Y7.1214 I0.0367 J0.0506 -G2 X2.415 Y7.1839 I0.0625 J0 -G1 X2.5551 Y7.1839 -G1 X2.5984 Y7.3172 -G1 X2.5984 Y7.3174 -G1 X1.768 Y7.3174 -G2 X1.7684 Y7.3163 I-0.0594 J-0.0195 -G1 X1.8093 Y7.1839 -G1 X1.9515 Y7.1839 -G2 X2.014 Y7.1214 I0 J-0.0625 -G2 X1.9882 Y7.0708 I-0.0625 J0 -G1 X1.8748 Y6.9884 -G1 X1.9182 Y6.8552 -G2 X1.9213 Y6.8358 I-0.0594 J-0.0193 -G2 X1.822 Y6.7853 I-0.0625 J0 -G1 X1.7087 Y6.8676 -G1 X1.5953 Y6.7853 -G2 X1.496 Y6.8358 I-0.0367 J0.0506 -G2 X1.4991 Y6.8551 I0.0625 J0 -G1 X1.5424 Y6.9884 -G1 X1.429 Y7.0708 -G2 X1.4032 Y7.1214 I0.0367 J0.0506 -G2 X1.4657 Y7.1839 I0.0625 J0 -G1 X1.6059 Y7.1839 -G1 X1.6492 Y7.3172 -G1 X1.6493 Y7.3174 -G1 X0.8188 Y7.3174 -G2 X0.8191 Y7.3164 I-0.0594 J-0.0195 -G1 X0.8601 Y7.1839 -G1 X1.0023 Y7.1839 -G2 X1.0648 Y7.1214 I0 J-0.0625 -G2 X1.039 Y7.0708 I-0.0625 J0 -G1 X0.9257 Y6.9884 -G1 X0.9689 Y6.8551 -G2 X0.972 Y6.8358 I-0.0594 J-0.0193 -G2 X0.8727 Y6.7853 I-0.0625 J0 -G1 X0.7594 Y6.8676 -G1 X0.646 Y6.7853 -G2 X0.5468 Y6.8358 I-0.0367 J0.0506 -G2 X0.5498 Y6.8552 I0.0625 J0 -G1 X0.5932 Y6.9884 -G1 X0.4798 Y7.0708 -G2 X0.4541 Y7.1214 I0.0367 J0.0506 -G2 X0.5166 Y7.1839 I0.0625 J0 -G1 X0.6567 Y7.1839 -G1 X0.6999 Y7.3172 -G1 X0.7 Y7.3174 -G1 X0.441 Y7.3174 -G1 X0.441 Y3.5986 -G1 X0.5468 Y3.5986 -G2 X0.5468 Y3.6006 I0.0625 J0.002 -G2 X0.5498 Y3.62 I0.0625 J0 -G1 X0.5932 Y3.7532 -G1 X0.4798 Y3.8356 -G2 X0.4541 Y3.8861 I0.0367 J0.0506 -G2 X0.5166 Y3.9486 I0.0625 J0 -G1 X0.6567 Y3.9486 -G1 X0.6999 Y4.0819 -G2 X0.8191 Y4.0811 I0.0594 J-0.0193 -G1 X0.8601 Y3.9486 -G1 X1.0023 Y3.9486 -G2 X1.0648 Y3.8861 I0 J-0.0625 -G2 X1.039 Y3.8356 I-0.0625 J0 -G1 X0.9257 Y3.7532 -G1 X0.9689 Y3.6199 -G2 X0.972 Y3.6006 I-0.0594 J-0.0193 -G2 X0.972 Y3.5986 I-0.0625 J0 -G1 X1.4961 Y3.5986 -G2 X1.496 Y3.6006 I0.0625 J0.002 -G2 X1.4991 Y3.6199 I0.0625 J0 -G1 X1.5424 Y3.7532 -G1 X1.429 Y3.8356 -G2 X1.4032 Y3.8861 I0.0367 J0.0506 -G2 X1.4657 Y3.9486 I0.0625 J0 -G1 X1.6059 Y3.9486 -G1 X1.6492 Y4.0819 -G2 X1.7684 Y4.081 I0.0594 J-0.0193 -G1 X1.8092 Y3.9486 -G1 X1.9515 Y3.9486 -G2 X2.014 Y3.8861 I0 J-0.0625 -G2 X1.9882 Y3.8356 I-0.0625 J0 -G1 X1.8748 Y3.7532 -G1 X1.9182 Y3.62 -G2 X1.9213 Y3.6006 I-0.0594 J-0.0193 -G2 X1.9212 Y3.5986 I-0.0625 J0 -G1 X2.4452 Y3.5986 -G2 X2.4452 Y3.6006 I0.0625 J0.002 -G2 X2.4483 Y3.62 I0.0625 J0 -G1 X2.4916 Y3.7532 -G1 X2.3783 Y3.8356 -G2 X2.3525 Y3.8861 I0.0367 J0.0506 -G2 X2.415 Y3.9486 I0.0625 J0 -G1 X2.5551 Y3.9486 -G1 X2.5984 Y4.0819 -G2 X2.7175 Y4.0811 I0.0594 J-0.0193 -G1 X2.7585 Y3.9486 -G1 X2.9007 Y3.9486 -G2 X2.9632 Y3.8861 I0 J-0.0625 -G2 X2.9375 Y3.8356 I-0.0625 J0 -G1 X2.8241 Y3.7532 -G1 X2.8674 Y3.6199 -G2 X2.8704 Y3.6006 I-0.0594 J-0.0193 -G2 X2.8704 Y3.5986 I-0.0625 J0 -G1 X3.3945 Y3.5986 -G2 X3.3945 Y3.6006 I0.0625 J0.002 -G2 X3.3975 Y3.6199 I0.0625 J0 -G1 X3.4408 Y3.7532 -G1 X3.3274 Y3.8356 -G2 X3.3017 Y3.8861 I0.0367 J0.0506 -G2 X3.3642 Y3.9486 I0.0625 J0 -G1 X3.5043 Y3.9486 -G1 X3.5477 Y4.0819 -G2 X3.6668 Y4.081 I0.0594 J-0.0193 -G1 X3.7077 Y3.9486 -G1 X3.8499 Y3.9486 -G2 X3.9124 Y3.8861 I0 J-0.0625 -G2 X3.8866 Y3.8356 I-0.0625 J0 -G1 X3.7733 Y3.7532 -G1 X3.8166 Y3.62 -G2 X3.8197 Y3.6006 I-0.0594 J-0.0193 -G2 X3.8197 Y3.5986 I-0.0625 J0 -G1 X4.3437 Y3.5986 -G2 X4.3437 Y3.6006 I0.0625 J0.002 -G2 X4.3467 Y3.62 I0.0625 J0 -G1 X4.3901 Y3.7532 -G1 X4.2767 Y3.8356 -G2 X4.2509 Y3.8861 I0.0367 J0.0506 -G2 X4.3134 Y3.9486 I0.0625 J0 -G1 X4.4535 Y3.9486 -G1 X4.4968 Y4.0819 -G2 X4.616 Y4.0811 I0.0594 J-0.0193 -G1 X4.6569 Y3.9486 -G1 X4.7992 Y3.9486 -G2 X4.8617 Y3.8861 I0 J-0.0625 -G2 X4.8359 Y3.8356 I-0.0625 J0 -G1 X4.7225 Y3.7532 -G1 X4.7658 Y3.6199 -G2 X4.7689 Y3.6006 I-0.0594 J-0.0193 -G2 X4.7688 Y3.5986 I-0.0625 J0 -G1 X5.293 Y3.5986 -G2 X5.2929 Y3.6006 I0.0625 J0.002 -G2 X5.296 Y3.6199 I0.0625 J0 -G1 X5.3393 Y3.7532 -G1 X5.2259 Y3.8356 -G2 X5.2001 Y3.8861 I0.0367 J0.0506 -G2 X5.2626 Y3.9486 I0.0625 J0 -G1 X5.4027 Y3.9486 -G1 X5.4461 Y4.0819 -G2 X5.5652 Y4.081 I0.0594 J-0.0193 -G1 X5.6061 Y3.9486 -G1 X5.7483 Y3.9486 -G2 X5.8108 Y3.8861 I0 J-0.0625 -G2 X5.7851 Y3.8356 I-0.0625 J0 -G1 X5.6717 Y3.7532 -G1 X5.7151 Y3.62 -G0 Z0.25 -G0 X5.459 Y3.5986 -G1 Z-0.05 F30 -G1 X5.552 Y3.5986 F10 -G1 X5.5055 Y3.6324 -G1 X5.459 Y3.5986 -G0 Z0.25 -G0 X3.5606 Y3.5986 -G1 Z-0.05 F30 -G1 X3.6536 Y3.5986 F10 -G1 X3.6071 Y3.6324 -G1 X3.5606 Y3.5986 -G0 Z0.25 -G0 X1.6622 Y3.5986 -G1 Z-0.05 F30 -G1 X1.7552 Y3.5986 F10 -G1 X1.7087 Y3.6324 -G1 X1.6622 Y3.5986 -G0 Z0.25 -G0 X0.7129 Y3.5986 -G1 Z-0.05 F30 -G1 X0.8059 Y3.5986 F10 -G1 X0.7594 Y3.6324 -G1 X0.7129 Y3.5986 -G0 Z0.25 -G0 X2.6113 Y3.5986 -G1 Z-0.05 F30 -G1 X2.7043 Y3.5986 F10 -G1 X2.6578 Y3.6324 -G1 X2.6113 Y3.5986 -G0 Z0.25 -G0 X4.5098 Y3.5986 -G1 Z-0.05 F30 -G1 X4.6028 Y3.5986 F10 -G1 X4.5563 Y3.6324 -G1 X4.5098 Y3.5986 - -(follow path 2) -G0 Z0.25 -G0 X0.2848 Y0.5504 -G1 Z-0.0625 F30 -G1 X14.5348 Y0.5504 F10 -G1 X14.5348 Y-0.0264 -G1 X0.2848 Y-0.0264 -G1 X0.2848 Y0.5504 -G0 Z0.25 -G0 X0.2848 Y1.1275 -G1 Z-0.0625 F30 -G1 X14.5348 Y1.1275 F10 -G1 X14.5348 Y0.5508 -G1 X0.2848 Y0.5508 -G1 X0.2848 Y1.1275 -G0 Z0.25 -G0 X0.2848 Y1.7049 -G1 Z-0.0625 F30 -G1 X14.5348 Y1.7049 F10 -G1 X14.5348 Y1.1281 -G1 X0.2848 Y1.1281 -G1 X0.2848 Y1.7049 -G0 Z0.25 -G0 X0.2848 Y2.282 -G1 Z-0.0625 F30 -G1 X14.5348 Y2.282 F10 -G1 X14.5348 Y1.7053 -G1 X0.2848 Y1.7053 -G1 X0.2848 Y2.282 -G0 Z0.25 -G0 X0.2848 Y2.8592 -G1 Z-0.0625 F30 -G1 X14.5348 Y2.8592 F10 -G1 X14.5348 Y2.2824 -G1 X0.2848 Y2.2824 -G1 X0.2848 Y2.8592 -G0 Z0.25 -G0 X0.2848 Y3.4363 -G1 Z-0.0625 F30 -G1 X14.5348 Y3.4363 F10 -G1 X14.5348 Y2.8596 -G1 X0.2848 Y2.8596 -G1 X0.2848 Y3.4363 -G0 Z0.25 -G0 X5.9859 Y4.0137 -G1 Z-0.0625 F30 -G1 X14.5348 Y4.0137 F10 -G1 X14.5348 Y3.4369 -G1 X5.9859 Y3.4369 -G1 X5.9859 Y4.0137 -G0 Z0.25 -G0 X5.9859 Y4.5908 -G1 Z-0.0625 F30 -G1 X14.5348 Y4.5908 F10 -G1 X14.5348 Y4.0141 -G1 X5.9859 Y4.0141 -G1 X5.9859 Y4.5908 -G0 Z0.25 -G0 X5.9859 Y5.1676 -G1 Z-0.0625 F30 -G1 X14.5348 Y5.1676 F10 -G1 X14.5348 Y4.5908 -G1 X5.9859 Y4.5908 -G1 X5.9859 Y5.1676 -G0 Z0.25 -G0 X5.9859 Y5.7447 -G1 Z-0.0625 F30 -G1 X14.5348 Y5.7447 F10 -G1 X14.5348 Y5.168 -G1 X5.9859 Y5.168 -G1 X5.9859 Y5.7447 -G0 Z0.25 -G0 X5.9859 Y6.3221 -G1 Z-0.0625 F30 -G1 X14.5348 Y6.3221 F10 -G1 X14.5348 Y5.7453 -G1 X5.9859 Y5.7453 -G1 X5.9859 Y6.3221 -G0 Z0.25 -G0 X5.9859 Y6.8992 -G1 Z-0.0625 F30 -G1 X14.5348 Y6.8992 F10 -G1 X14.5348 Y6.3225 -G1 X5.9859 Y6.3225 -G1 X5.9859 Y6.8992 -G0 Z0.25 -G0 X5.9859 Y7.4764 -G1 Z-0.0625 F30 -G1 X14.5348 Y7.4764 F10 -G1 X14.5348 Y6.8996 -G1 X5.9859 Y6.8996 -G1 X5.9859 Y7.4764 -G0 Z0.25 -G0 X0.2848 Y7.4736 -G1 Z-0.0625 F30 -G1 X5.9848 Y7.4736 F10 -G1 X5.9848 Y3.4349 -G1 X0.2848 Y3.4349 -G1 X0.2848 Y7.4736 - -(profile 3) -G0 Z0.25 -T0 M6 -G0 X0.0973 Y-0.3389 -G1 Z-0.15 F30 -G1 X12.9877 Y-0.3389 F20 -G1 X13.4877 Y-0.3389 -G1 X14.7223 Y-0.3389 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 X7.2382 Y7.7861 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 X-0.0277 Y1.0339 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.3 F30 -G1 X12.9877 Y-0.3389 F20 -G1 X13.4877 Y-0.3389 -G1 X14.7223 Y-0.3389 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 X7.2382 Y7.7861 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 X-0.0277 Y1.0339 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.45 F30 -G1 X12.9877 Y-0.3389 F20 -G1 X13.4877 Y-0.3389 -G1 X14.7223 Y-0.3389 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 X7.2382 Y7.7861 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 X-0.0277 Y1.0339 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.6 F30 -G1 X12.9877 Y-0.3389 F20 -G1 X13.4877 Y-0.3389 -G1 X14.7223 Y-0.3389 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 X7.2382 Y7.7861 -G1 X0.0973 Y7.7861 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 X-0.0277 Y1.0339 -G1 X-0.0277 Y-0.2139 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.75 F30 -G1 X12.9877 Y-0.3389 F20 -G1 Z-0.6 F30 -G1 X13.4877 Y-0.3389 F20 -G1 Z-0.75 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 Z-0.6 F30 -G1 X7.2382 Y7.7861 F20 -G1 Z-0.75 F30 -G1 X0.0973 Y7.7861 F20 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 Z-0.6 F30 -G1 X-0.0277 Y1.0339 F20 -G1 Z-0.75 F30 -G1 X-0.0277 Y-0.2139 F20 -G3 X0.0973 Y-0.3389 I0.125 J0 -G1 Z-0.85 F30 -G1 X12.9877 Y-0.3389 F20 -G1 Z-0.6 F30 -G1 X13.4877 Y-0.3389 F20 -G1 Z-0.85 F30 -G1 X14.7223 Y-0.3389 F20 -G3 X14.8473 Y-0.2139 I0 J0.125 -G1 X14.8473 Y7.6611 -G3 X14.7223 Y7.7861 I-0.125 J0 -G1 X7.7382 Y7.7861 -G1 Z-0.6 F30 -G1 X7.2382 Y7.7861 F20 -G1 Z-0.85 F30 -G1 X0.0973 Y7.7861 F20 -G3 X-0.0277 Y7.6611 I0 J-0.125 -G1 X-0.0277 Y1.5339 -G1 Z-0.6 F30 -G1 X-0.0277 Y1.0339 F20 -G1 Z-0.85 F30 -G1 X-0.0277 Y-0.2139 F20 -G3 X0.0973 Y-0.3389 I0.125 J0 -G0 Z0.25 -M5 -M30 diff --git a/gcode/testsquare.nc b/gcode/testsquare.nc deleted file mode 100644 index 59613079..00000000 --- a/gcode/testsquare.nc +++ /dev/null @@ -1,18 +0,0 @@ -0:(Generated by PartKam Version 0.05) -1: -2:G20 G90 G40 -3: -4:(follow path 1) -5:G0 Z0.1 -6:T0 M6 -7:G17 -8:M3 -9:G0 X4.675 Y0.8438 -10:G1 Z-0.75 F30 -11:G1 X9.675 Y0.8438 F60 -12:G1 X9.675 Y6.8438 -13:G1 X4.675 Y5.8438 -14:G1 X4.675 Y0.8438 -15:G0 Z0.1 -16:M5 -17:M30 diff --git a/gcode/testsquare1.nc b/gcode/testsquare1.nc deleted file mode 100644 index 9c423f87..00000000 --- a/gcode/testsquare1.nc +++ /dev/null @@ -1,22 +0,0 @@ -(Generated by PartKam Version 0.05) - -G20 G90 G40 - -(profile 1) -G0 Z0.1 -T0 M6 -G17 -M3 -G0 X4.675 Y0.7188 -G1 Z-0.1 F30 -G1 X9.675 Y0.7188 F60 -G3 X9.8 Y0.8438 I0 J0.125 -G1 X9.8 Y5.8438 -G3 X9.675 Y5.9688 I-0.125 J0 -G1 X4.675 Y5.9688 -G3 X4.55 Y5.8438 I0 J-0.125 -G1 X4.55 Y0.8438 -G3 X4.675 Y0.7188 I0.125 J0 -G0 Z0.1 -M5 -M30 diff --git a/holeyrequirements.txt b/holeyrequirements.txt new file mode 100644 index 00000000..c014a5ff --- /dev/null +++ b/holeyrequirements.txt @@ -0,0 +1,22 @@ +Click==7.0 +Flask==1.0.2 +Flask-Mobility==0.1.1 +Flask-SocketIO==3.0.2 +gevent==1.3.7 +greenlet==0.4.15 +itsdangerous==0.24 +Jinja2>=2.10.1 +MarkupSafe==1.0 +numpy==1.16.2 +scipy==1.3.1 +opencv-python==3.4.3.18 +pyserial==3.4 +python-engineio==2.3.2 +python-socketio==2.0.0 +schedule==0.5.0 +six==1.11.0 +Werkzeug==0.14.1 +psutil +gpiozero + + diff --git a/main-onedir.spec b/main-onedir.spec new file mode 100644 index 00000000..7698cec6 --- /dev/null +++ b/main-onedir.spec @@ -0,0 +1,34 @@ +# -*- mode: python ; coding: utf-8 -*- + +block_cipher = None + + +a = Analysis(['main.py'], + pathex=['C:\\Windows\\System32\\downlevel', 'C:\\Users\\john\\PycharmProjects\\WebControl'], + binaries=[], + datas=[('templates', 'templates'), ('firmware','firmware'), ('static', 'static'), ('tools', 'tools'), ('docs','docs'), ('defaultwebcontrol.json', '.')], + hiddenimports=['flask', 'flask-misaka', 'clr', 'gevent', 'gevent-websocket', 'engineio.async_gevent', 'distro', 'markdown'], + excludes=[], + win_no_prefer_redirects=False, + win_private_assemblies=False, + cipher=block_cipher, + noarchive=False) +pyz = PYZ(a.pure, a.zipped_data, + cipher=block_cipher) +exe = EXE(pyz, + a.scripts, + [], + exclude_binaries=True, + name='webcontrol', + debug=False, + strip=False, + upx=True, + console=True, + icon = 'webcontrolicon_256px.ico' ) +coll = COLLECT(exe, + a.binaries, + a.zipfiles, + a.datas, + strip=False, + upx=True, + name='main') diff --git a/main.py b/main.py index 24b3f291..fc440063 100644 --- a/main.py +++ b/main.py @@ -1,50 +1,84 @@ # main.py from app import app, socketio from gevent import monkey +import webbrowser +import socket +import math +import os +import subprocess +import sys monkey.patch_all() + + import schedule import time import threading import json -from flask import Flask, jsonify, render_template, current_app, request, flash +from flask import Flask, jsonify, render_template, current_app, request, flash, Response, send_file, send_from_directory from flask_mobility.decorators import mobile_template from werkzeug import secure_filename from Background.UIProcessor import UIProcessor # do this after socketio is declared +from Background.LogStreamer import LogStreamer # do this after socketio is declared +from Background.WebMCPProcessor import WebMCPProcessor +from Background.WebMCPProcessor import ConsoleProcessor from DataStructures.data import Data from Connection.nonVisibleWidgets import NonVisibleWidgets +from WebPageProcessor.webPageProcessor import WebPageProcessor + from os import listdir from os.path import isfile, join - +import sys app.data = Data() app.nonVisibleWidgets = NonVisibleWidgets() app.nonVisibleWidgets.setUpData(app.data) app.data.config.computeSettings(None, None, None, True) +app.data.config.parseFirmwareVersions() +version = sys.version_info # this is for python newer than 3.5 +if version[:2] > (3, 5): + app.data.pythonVersion35 = False # set data flag + print("Using routines for Python > 3.5") +else: + app.data.pythonVersion35 = True # set data flag + print("Using routines for Python == 3.5") app.data.units = app.data.config.getValue("Computed Settings", "units") +app.data.tolerance = app.data.config.getValue("Computed Settings", "tolerance") +app.data.distToMove = app.data.config.getValue("Computed Settings", "distToMove") +app.data.distToMoveZ = app.data.config.getValue("Computed Settings", "distToMoveZ") +app.data.unitsZ = app.data.config.getValue("Computed Settings", "unitsZ") app.data.comport = app.data.config.getValue("Maslow Settings", "COMport") -if app.data.units == "INCHES": - scale = 1.0 -else: - scale = 25.4 app.data.gcodeShift = [ - float(app.data.config.getValue("Advanced Settings", "homeX")) / scale, - float(app.data.config.getValue("Advanced Settings", "homeY")) / scale, + float(app.data.config.getValue("Advanced Settings", "homeX")), + float(app.data.config.getValue("Advanced Settings", "homeY")), ] + +version = sys.version_info + +if version[:2] > (3, 5): + app.data.pythonVersion35 = False + print("Using routines for Python > 3.5") +else: + app.data.pythonVersion35 = True + print("Using routines for Python == 3.5") + +app.data.firstRun = False # app.previousPosX = 0.0 # app.previousPosY = 0.0 app.UIProcessor = UIProcessor() +app.webPageProcessor = WebPageProcessor(app.data) +app.LogStreamer = LogStreamer() -## this runs the scheduler to check for connections +## this defines the schedule for running the serial port open connection def run_schedule(): while 1: schedule.run_pending() time.sleep(1) - +## this runs the scheduler to check for connections app.th = threading.Thread(target=run_schedule) app.th.daemon = True app.th.start() @@ -54,38 +88,265 @@ def run_schedule(): app.th1.daemon = True app.th1.start() -# write settings file to disk: -# from settings import settings -# settings = settings.getJSONSettings() -# with open('webcontrol.json', 'w') as outfile: -# json.dump(settings,outfile, sort_keys=True, indent=4, ensure_ascii=False) +## this runs the thread that sends debugging messages to the terminal and webmcp (if active) +app.th2 = threading.Thread(target=app.data.consoleProcessor.start) +app.th2.daemon = True +app.th2.start() -# read settings file from disk: +## uithread set to None.. will be activated upon first websocket connection from browser +app.uithread = None +## uithread set to None.. will be activated upon first websocket connection from webmcp +app.mcpthread = None + +## logstreamerthread set to None.. will be activated upon first websocket connection from log streamer browser +app.logstreamerthread = None + +def web_input_command(cmd, source): + if (len(cmd) > 2): # pull off the distance if it is there + distance = cmd[2] # distance is the third list element + else: + distance = 0 # if it isn't then put a 0 value in so no error is thrown + message = 'none' + if ('gcode' in cmd): # gcode commands found in gpioactions like start the gcode file cut, pause current cut, resume from pause, stop the cut, move sled home + print ('gcode selected') + if ('startRun' in cmd): + print ('start gcode ',source, ' requested') + app.data.actions.processAction({"data":{"command":"startRun","arg":"","arg1":""}}) + message = {"data":{source:"started"}} + elif ('pauseRun' in cmd): + if (app.data.uploadFlag == 1): + print ('pause gcode ',source, ' requested') + app.data.actions.processAction({"data":{"command":"pauseRun","arg":"","arg1":""}}) + message = {"data":{source:"paused"}} + elif (app.data.uploadFlag == 2): + print ('continue gcode ', source, ' requested') + app.data.actions.processAction({"data":{"command":"resumeRun","arg":"","arg1":""}}) + message = {"data":{source:"resumed"}} + else: + print("not running - no pause") + message = {"data":{source:"No Pause - not running"}} + elif (cmd[1] == 'resumeRun'): + print ('continue gcode ',source, ' requested') + app.data.actions.processAction({"data":{"command":"resumeRun","arg":"","arg1":""}}) + message = {"data":{source:"resumed"}} + elif (cmd[1] == 'stopRun'): + print ('stop gcode', source, ' requested') + app.data.actions.processAction({"data":{"command":"stopRun","arg":"","arg1":""}}) + message = {"data":{source:"stopped"}} + elif('home' in cmd): + print (source, ' says go home') + app.data.actions.processAction({"data":{"command":"home","arg":"","arg1":""}}) + message = {"data":{source:"movetoHome"}} + else: + print(cmd, " Invalid command") + message = {"data":{"gcode":"NONE selected"}} + if ('zAxis' in cmd): # this command set works with the z axis + print ('zaxis selected ', source) + if('raise' in cmd): + print (source, ' zaxis', distance, 'raise') + app.data.actions.processAction({"data":{"command":"moveZ","arg":"raise","arg1":distance}}) + message = {"data":{source:"raise"}} + elif('lower' in cmd): + print (source, ' zaxis', distance, 'lower') + app.data.actions.processAction({"data":{"command":"moveZ","arg":"lower","arg1":distance}}) + message = {"data":{source:"Lower"}} + elif('stopZ' in cmd ): + print (source, ' zaxis stop ', source) + app.data.actions.processAction({"data":{"command":"stopZ","arg":"","arg1":""}}) + message = {"data":{source:"stopZ"}} + elif('defineZ0' in cmd): + print ('new Z axis zero point via ', source) + app.data.actions.processAction({"data":{"command":"defineZ0","arg":"","arg1":""}}) + message = {"data":{source:"defineZ"}} # this command set will move or change the sled + else: + print(cmd, " Invalid command") + message = {"data":{source:" NONE selected"}} + if ('sled' in cmd or 'move' in cmd): + if('up' in cmd): + print (source, ' move', distance, 'up') + app.data.actions.processAction({"data":{"command":"move","arg":"up","arg1":distance}}) + message = {"data":{source:"up"}} + elif('down' in cmd): + print (source, ' move', distance, 'down') + app.data.actions.processAction({"data":{"command":"move","arg":"down","arg1":distance}}) + message = {"data":{source:"down"}} + elif('left' in cmd): + print (source, ' move', distance, 'left') + app.data.actions.processAction({"data":{"command":"move","arg":"left","arg1":distance}}) + message = {"data":{source:"left"}} + elif('right' in cmd): + print (source, ' move', distance, 'right') + app.data.actions.processAction({"data":{"command":"move","arg":"right","arg1":distance}}) + message = {"data":{source:"right"}} + elif('home' in cmd): + print ('go home via ', source) + app.data.actions.processAction({"data":{"command":"home","arg":"","arg1":""}}) + message = {"data":{source:"movetoHome"}} + elif('defineHome' in cmd): + print ('new home set via ', source, ' to ', app.data.xval ,', ', app.data.yval) + app.data.actions.processAction({"data":{"command":"defineHome","arg":app.data.xval,"arg1":app.data.yval}}) + message = {"data":{source:"NewHome"}} + else: + print(cmd, " Invalid command") + message = {"data":{"sled":"NONE selected"}} + if ('system' in cmd): # this command set will adjust the system including pendant connection status and system power + print ('system selected via ', source) + if ('exit' in cmd): + print("system shutdown requested") + if (app.data.uploadFlag == 0): + os._exit(0) + else: + app.data.actions.processAction({"data":{"command":"stopRun","arg":"","arg1":""}}) + print("denied: running code. Code stopped near try again") + message = {"data":{"system":"shutdownAttempt"}} + elif ('connected' in cmd): + print("wiimote connected") + message = {"data":{"system":"Connect"}} + app.data.wiiPendantConnected = True + elif ('disconnect' in cmd): + print("wiimote disconnect") + app.data.wiiPendantConnected = False + message = {"data":{"system":"Disconnect"}} + else: + print(cmd, " Invalid command") + message = {"data":{"system":"NONE selected"}} + return(message) @app.route("/") @mobile_template("{mobile/}") def index(template): - # print template - current_app._get_current_object() - thread = socketio.start_background_task( - app.UIProcessor.start, current_app._get_current_object() - ) - thread.start() - if not app.data.connectionStatus: - app.data.serialPort.openConnection() + app.data.logger.resetIdler() + macro1Title = (app.data.config.getValue("Maslow Settings", "macro1_title"))[:6] + macro2Title = (app.data.config.getValue("Maslow Settings", "macro2_title"))[:6] if template == "mobile/": - return render_template("frontpage_mobile.html") + return render_template("frontpage3d_mobile.html", modalStyle="modal-lg", macro1_title=macro1Title, macro2_title=macro2Title) else: - return render_template("frontpage.html") + return render_template("frontpage3d.html", modalStyle="mw-100 w-75", macro1_title=macro1Title, macro2_title=macro2Title) + +@app.route('/GPIO', methods=['PUT', 'GET']) +def remote_function_call(): + ''' + MaslowButton.py starts as a separate python process if the maslow setting flag is true + The GPIO is for raspberry pi general purpoe input/output such as button and LED hardware physically attached to the raspberry pi + When those buttons are pressed, the seaparate process issues an HTTP/PUT request and this method handles it. The /LED section below sends information for LEDs + ''' + if (request.method == "PUT"): + print ("button function call") + message = {"data":{"gpio":"selected"}} + result = request.data + result = result.decode('utf-8') + resultlist = result.split(':') + print ('resultlist', resultlist) + message = web_input_command(resultlist, "button") + print(message) + resp = jsonify(message) + resp.status_code = 200 # or whatever the correct number should be + return (resp) + + if (request.method == "GET"): + setValues = app.data.config.getJSONSettingSection("GPIO Settings") + return (jsonify(setValues)) + +@app.route('/LED', methods=['PUT','GET']) +def getLEDinfo(): + ''' + The MaslowButton.py has provisions for an on-system display. + This is the LED method responds MaslowButton.py requests via HTTP/GET + and processses the repeated inquiry every 2-5 seconds. + Upload flag signifies system state as running, paused, or stopped, + Moving flag indicates a stopped cut condition, but the sled is moving + zmove is the z axis moving + ''' + if (request.method == 'GET'): + try: + message = {"data":{"index": str(app.data.gcodeIndex), \ + "flag": str(app.data.uploadFlag), \ + "moving": str(app.data.sledMoving), \ + "zMove": str(app.data.zMoving), \ + "wiiPendantPresent": str(app.data.config.getValue("Maslow Settings","wiiPendantPresent")), \ + "wiiconnected" : str(int(app.data.wiiPendantConnected)), \ + "clidisplay" : str(app.data.config.getValue("Maslow Settings","clidisplay")), \ + "sled_location_X": str(app.data.xval), \ + "sled_location_y": str(app.data.yval), \ + #"sled_location_z": str(app.data.zval), \ + #This part works + "home_location_x": str(app.data.config.getValue("Advanced Settings","homeX")), \ + "home_location_y": str(app.data.config.getValue("Advanced Settings","homeY")), \ + #this part does not work + "gcode_max_x": str(app.data.gcode_x_max), \ + "gcode_min_x": str(app.data.gcode_x_min), \ + "gcode_max_y": str(app.data.gcode_y_max), \ + "gcode_min_y": str(app.data.gcode_y_min)}} #assemble json string + #print(message) + resp = jsonify(message) # java script object notation convrsion of the message + resp.status_code = 200 + return (resp) # send the message + except: + message = jsonify({"data":{"error":"no data"}}) # on error, respond with something rather than nothing + resp = jsonify(message) + resp.status_code = 404 # or whatever the correct number should be + return (resp) + +@app.route('/pendant', methods=['PUT', 'GET']) +def WiiMoteInput(): + ''' + This is for the raspberry pi + The MaslowButton.py runs as a separate MaslowPendant.py process + that interacts with this function via HTTP/PUT + and this routine interprets those commands from the wii to move Maslow + ''' + print ("pendant function call") + result = request.data #pull off the data parameters + #print (result) + result = result.decode('utf-8') # convert the binary data into text + resultlist = result.split(':') #take the input and cut it up into list pieces + print (resultlist) + message = web_input_command(resultlist, "wii") + print(message) + resp = jsonify(message) + resp.status_code = 200 + return (resp) + +@app.route("/controls") +@mobile_template("/controls/{mobile/}") +def controls(template): + app.data.logger.resetIdler() + macro1Title = (app.data.config.getValue("Maslow Settings", "macro1_title"))[:6] + macro2Title = (app.data.config.getValue("Maslow Settings", "macro2_title"))[:6] + if template == "/controls/mobile/": + return render_template("frontpage3d_mobilecontrols.html", modalStyle="modal-lg", isControls=True, macro1_title=macro1Title, macro2_title=macro2Title) + else: + return render_template("frontpage3d.html", modalStyle="mw-100 w-75", macro1_title=macro1Title, macro2_title=macro2Title) + +@app.route("/text") +@mobile_template("/text/{mobile/}") +def text(template): + app.data.logger.resetIdler() + macro1Title = (app.data.config.getValue("Maslow Settings", "macro1_title"))[:6] + macro2Title = (app.data.config.getValue("Maslow Settings", "macro2_title"))[:6] + if template == "/text/mobile": + return render_template("frontpageText_mobile.html", modalStyle="modal-lg", isControls=True, macro1_title=macro1Title, macro2_title=macro2Title) + else: + return render_template("frontpageText.html", modalStyle="mw-100 w-75", macro1_title=macro1Title, macro2_title=macro2Title) + +@app.route("/logs") +@mobile_template("/logs/{mobile/}") +def logs(template): + print("here") + app.data.logger.resetIdler() + if template == "/logs/mobile/": + return render_template("logs.html") + else: + return render_template("logs.html") @app.route("/maslowSettings", methods=["POST"]) def maslowSettings(): + app.data.logger.resetIdler() if request.method == "POST": result = request.form app.data.config.updateSettings("Maslow Settings", result) - # setValues = app.data.config.getJSONSettingSection("Maslow Settings") message = {"status": 200} resp = jsonify(message) resp.status_code = 200 @@ -94,6 +355,7 @@ def maslowSettings(): @app.route("/advancedSettings", methods=["POST"]) def advancedSettings(): + app.data.logger.resetIdler() if request.method == "POST": result = request.form app.data.config.updateSettings("Advanced Settings", result) @@ -105,6 +367,7 @@ def advancedSettings(): @app.route("/webControlSettings", methods=["POST"]) def webControlSettings(): + app.data.logger.resetIdler() if request.method == "POST": result = request.form app.data.config.updateSettings("WebControl Settings", result) @@ -114,12 +377,84 @@ def webControlSettings(): return resp +@app.route("/cameraSettings", methods=["POST"]) +def cameraSettings(): + app.data.logger.resetIdler() + if request.method == "POST": + result = request.form + app.data.config.updateSettings("Camera Settings", result) + message = {"status": 200} + resp = jsonify(message) + resp.status_code = 200 + return resp + +@app.route("/gpioSettings", methods=["POST"]) +def gpioSettings(): + app.data.logger.resetIdler() + if request.method == "POST": + result = request.form + app.data.config.updateSettings("GPIO Settings", result) + message = {"status": 200} + resp = jsonify(message) + resp.status_code = 200 + # restart button service here + # this button service resets the button maps for the updated gpio pins + print("restarting maslow button service") + try: + subprocess.run(['sudo','/usr/local/etc/MaslowButtonRestart.sh']) + print("restarted maslow button service") + except: + print("error restarting button service") + return resp + @app.route("/uploadGCode", methods=["POST"]) def uploadGCode(): + app.data.logger.resetIdler() if request.method == "POST": - f = request.files["file"] - app.data.gcodeFile.filename = "gcode/" + secure_filename(f.filename) - f.save(app.data.gcodeFile.filename) + result = request.form + directory = result["selectedDirectory"] + #print(directory) + f = request.files.getlist("file[]") + print(f) + home = app.data.config.getHome() + app.data.config.setValue("Computed Settings", "lastSelectedDirectory", directory) + + if len(f) > 0: + firstFile = f[0] + for file in f: + app.data.gcodeFile.filename = home + "/.WebControl/gcode/" + directory + "/" + secure_filename( + file.filename) + file.save(app.data.gcodeFile.filename) + app.data.gcodeFile.filename = home + "/.WebControl/gcode/" + directory + "/" + secure_filename(firstFile.filename) + returnVal = app.data.gcodeFile.loadUpdateFile() + if returnVal: + message = {"status": 200} + resp = jsonify(message) + resp.status_code = 200 + return resp + else: + message = {"status": 500} + resp = jsonify(message) + resp.status_code = 500 + return resp + else: + message = {"status": 500} + resp = jsonify(message) + resp.status_code = 500 + return resp + + +@app.route("/openGCode", methods=["POST"]) +def openGCode(): + app.data.logger.resetIdler() + if request.method == "POST": + f = request.form["selectedGCode"] + app.data.console_queue.put("selectedGcode="+str(f)) + tDir = f.split("/") + app.data.config.setValue("Computed Settings","lastSelectedDirectory",tDir[0]) + home = app.data.config.getHome() + app.data.gcodeFile.filename = home+"/.WebControl/gcode/" + f + app.data.config.setValue("Maslow Settings", "openFile", tDir[1]) returnVal = app.data.gcodeFile.loadUpdateFile() if returnVal: message = {"status": 200} @@ -132,13 +467,72 @@ def uploadGCode(): resp.status_code = 500 return resp - -@app.route("/openGCode", methods=["POST"]) -def openGCode(): +@app.route("/saveGCode", methods=["POST"]) +def saveGCode(): + app.data.logger.resetIdler() if request.method == "POST": - f = request.form["selectedGCode"] - app.data.gcodeFile.filename = "gcode/" + f + print(request.form) + f = request.form["fileName"] + d = request.form["selectedDirectory"] + app.data.console_queue.put("selectedGcode="+f) + app.data.config.setValue("Computed Settings", "lastSelectedDirectory",d) + home = app.data.config.getHome() + returnVal = app.data.gcodeFile.saveFile(f, home+"/.WebControl/gcode/"+d) + ''' + tDir = f.split("/") + app.data.config.setValue("Computed Settings","lastSelectedDirectory",tDir[0]) + home = app.data.config.getHome() + app.data.gcodeFile.filename = home+"/.WebControl/gcode/" + f + app.data.config.setValue("Maslow Settings", "openFile", tDir[1]) returnVal = app.data.gcodeFile.loadUpdateFile() + ''' + if returnVal: + app.data.config.setValue("Maslow Settings", "openFile", f) + message = {"status": 200} + resp = jsonify(message) + resp.status_code = 200 + return resp + else: + message = {"status": 500} + resp = jsonify(message) + resp.status_code = 500 + return resp + +@app.route("/openBoard", methods=["POST"]) +def openBoard(): + app.data.logger.resetIdler() + if request.method == "POST": + f = request.form["selectedBoard"] + app.data.console_queue.put("selectedBoard="+str(f)) + tDir = f.split("/") + app.data.config.setValue("Computed Settings","lastSelectedBoardDirectory",tDir[0]) + home = app.data.config.getHome() + app.data.gcodeFile.filename = home+"/.WebControl/boards/" + f + app.data.config.setValue("Maslow Settings", "openBoardFile", tDir[1]) + returnVal = app.data.boardManager.loadBoard(home+"/.WebControl/boards/"+f) + if returnVal: + message = {"status": 200} + resp = jsonify(message) + resp.status_code = 200 + return resp + else: + message = {"status": 500} + resp = jsonify(message) + resp.status_code = 500 + return resp + +@app.route("/saveBoard", methods=["POST"]) +def saveBoard(): + app.data.logger.resetIdler() + if request.method == "POST": + print(request.form) + f = request.form["fileName"] + d = request.form["selectedDirectory"] + app.data.console_queue.put("selectedBoard="+f) + app.data.config.setValue("Computed Settings", "lastSelectedBoardDirectory",d) + home = app.data.config.getHome() + returnVal = app.data.boardManager.saveBoard(f, home+"/.WebControl/boards/"+d) + app.data.config.setValue("Maslow Settings", "openBoardFile", f) if returnVal: message = {"status": 200} resp = jsonify(message) @@ -153,9 +547,11 @@ def openGCode(): @app.route("/importFile", methods=["POST"]) def importFile(): + app.data.logger.resetIdler() if request.method == "POST": f = request.files["file"] - secureFilename = "imports\\" + secure_filename(f.filename) + home = app.data.config.getHome() + secureFilename = home+"/.WebControl/imports/" + secure_filename(f.filename) f.save(secureFilename) returnVal = app.data.importFile.importGCini(secureFilename) if returnVal: @@ -169,9 +565,67 @@ def importFile(): resp.status_code = 500 return resp +@app.route("/importFileWCJSON", methods=["POST"]) +def importFileJSON(): + app.data.logger.resetIdler() + if request.method == "POST": + f = request.files["file"] + home = app.data.config.getHome() + secureFilename = home + "/.WebControl/imports/" + secure_filename(f.filename) + f.save(secureFilename) + returnVal = app.data.importFile.importWebControlJSON(secureFilename) + if returnVal: + message = {"status": 200} + resp = jsonify(message) + resp.status_code = 200 + return resp + else: + message = {"status": 500} + resp = jsonify(message) + resp.status_code = 500 + return resp + +@app.route("/importRestoreWebControl", methods=["POST"]) +def importRestoreWebControl(): + app.data.logger.resetIdler() + if request.method == "POST": + f = request.files["file"] + home = app.data.config.getHome() + secureFilename = home + "/" + secure_filename(f.filename) + f.save(secureFilename) + returnVal = app.data.actions.restoreWebControl(secureFilename) + if returnVal: + message = {"status": 200} + resp = jsonify(message) + resp.status_code = 200 + return resp + else: + message = {"status": 500} + resp = jsonify(message) + resp.status_code = 500 + return resp + +@app.route("/sendGCode", methods=["POST"]) +def sendGcode(): + app.data.logger.resetIdler() + #print(request.form)#["gcodeInput"]) + if request.method == "POST": + returnVal = app.data.actions.sendGCode(request.form["gcode"].rstrip()) + if returnVal: + message = {"status": 200} + resp = jsonify("success") + resp.status_code = 200 + return resp + else: + message = {"status": 500} + resp = jsonify("failed") + resp.status_code = 500 + return resp + @app.route("/triangularCalibration", methods=["POST"]) def triangularCalibration(): + app.data.logger.resetIdler() if request.method == "POST": result = request.form motorYoffsetEst, rotationRadiusEst, chainSagCorrectionEst, cut34YoffsetEst = app.data.actions.calibrate( @@ -197,9 +651,38 @@ def triangularCalibration(): resp.status_code = 500 return resp +@app.route("/holeyCalibration", methods=["POST"]) +def holeyCalibration(): + app.data.logger.resetIdler() + if request.method == "POST": + result = request.form + motorYoffsetEst, distanceBetweenMotors, leftChainTolerance, rightChainTolerance, calibrationError = app.data.actions.holeyCalibrate( + result + ) + # print(returnVal) + if motorYoffsetEst: + message = { + "status": 200, + "data": { + "motorYoffset": motorYoffsetEst, + "distanceBetweenMotors": distanceBetweenMotors, + "leftChainTolerance": leftChainTolerance, + "rightChainTolerance": rightChainTolerance, + "calibrationError": calibrationError + }, + } + resp = jsonify(message) + resp.status_code = 200 + return resp + else: + message = {"status": 500} + resp = jsonify(message) + resp.status_code = 500 + return resp @app.route("/opticalCalibration", methods=["POST"]) def opticalCalibration(): + app.data.logger.resetIdler() if request.method == "POST": result = request.form message = {"status": 200} @@ -215,6 +698,7 @@ def opticalCalibration(): @app.route("/quickConfigure", methods=["POST"]) def quickConfigure(): + app.data.logger.resetIdler() if request.method == "POST": result = request.form app.data.config.updateQuickConfigure(result) @@ -223,278 +707,295 @@ def quickConfigure(): resp.status_code = 200 return resp +@app.route("/editGCode", methods=["POST"]) +def editGCode(): + app.data.logger.resetIdler() + #print(request.form["gcode"]) + if request.method == "POST": + returnVal = app.data.actions.updateGCode(request.form["gcode"].rstrip()) + if returnVal: + message = {"status": 200} + resp = jsonify("success") + resp.status_code = 200 + return resp + else: + message = {"status": 500} + resp = jsonify("failed") + resp.status_code = 500 + return resp + +@app.route("/downloadDiagnostics", methods=["GET"]) +def downloadDiagnostics(): + app.data.logger.resetIdler() + if request.method == "GET": + returnVal = app.data.actions.downloadDiagnostics() + if returnVal != False: + print(returnVal) + return send_file(returnVal, as_attachment=True) + else: + resp = jsonify("failed") + resp.status_code = 500 + return resp + +@app.route("/backupWebControl", methods=["GET"]) +def backupWebControl(): + app.data.logger.resetIdler() + if request.method == "GET": + returnVal = app.data.actions.backupWebControl() + if returnVal != False: + print(returnVal) + return send_file(returnVal) + else: + resp = jsonify("failed") + resp.status_code = 500 + return resp + + +@app.route("/editBoard", methods=["POST"]) +def editBoard(): + app.data.logger.resetIdler() + if request.method == "POST": + returnVal = app.data.boardManager.editBoard(request.form) + if returnVal: + resp = jsonify("success") + resp.status_code = 200 + return resp + else: + resp = jsonify("failed") + resp.status_code = 500 + return resp + +@app.route("/trimBoard", methods=["POST"]) +def trimBoard(): + app.data.logger.resetIdler() + if request.method == "POST": + returnVal = app.data.boardManager.trimBoard(request.form) + if returnVal: + resp = jsonify("success") + resp.status_code = 200 + return resp + else: + resp = jsonify("failed") + resp.status_code = 500 + return resp + +@app.route("/assets/") +def sendDocs(path): + print(path) + return send_from_directory('docs/assets/', path) + + +@socketio.on("checkInRequested", namespace="/WebMCP") +def checkInRequested(): + socketio.emit("checkIn", namespace="/WebMCP") + + +@socketio.on("connect", namespace="/WebMCP") +def watchdog_connect(): + app.data.console_queue.put("watchdog connected") + app.data.console_queue.put(request.sid) + socketio.emit("connect", namespace="/WebMCP") + if app.mcpthread == None: + app.data.console_queue.put("going to start mcp thread") + app.mcpthread = socketio.start_background_task( + app.data.mcpProcessor.start, current_app._get_current_object() + ) + app.data.console_queue.put("created mcp thread") + app.mcpthread.start() + app.data.console_queue.put("started mcp thread") + @socketio.on("my event", namespace="/MaslowCNC") def my_event(msg): - print(msg["data"]) + app.data.console_queue.put(msg["data"]) + + +@socketio.on("modalClosed", namespace="/MaslowCNC") +def modalClosed(msg): + app.data.logger.resetIdler() + data = json.dumps({"title": msg["data"]}) + socketio.emit("message", {"command": "closeModals", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", ) + + +@socketio.on("contentModalClosed", namespace="/MaslowCNC") +def contentModalClosed(msg): + #Note, this shouldn't be called anymore + #todo: cleanup + app.data.logger.resetIdler() + data = json.dumps({"title": msg["data"]}) + print(data) + #socketio.emit("message", {"command": "closeContentModals", "data": data, "dataFormat": "json"}, + # namespace="/MaslowCNC", ) + +''' +todo: cleanup +not used +@socketio.on("actionModalClosed", namespace="/MaslowCNC") +def actionModalClosed(msg): + app.data.logger.resetIdler() + data = json.dumps({"title": msg["data"]}) + socketio.emit("message", {"command": "closeActionModals", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", ) +''' + +@socketio.on("alertModalClosed", namespace="/MaslowCNC") +def alertModalClosed(msg): + app.data.logger.resetIdler() + data = json.dumps({"title": msg["data"]}) + socketio.emit("message", {"command": "closeAlertModals", "data": data, "dataFormat": "json"}, + namespace="/MaslowCNC", ) @socketio.on("requestPage", namespace="/MaslowCNC") def requestPage(msg): - if msg["data"]["page"] == "maslowSettings": - setValues = app.data.config.getJSONSettingSection("Maslow Settings") - # because this page allows you to select the comport from a list that is not stored in webcontrol.json, we need to package and send the list of comports - # Todo:? change it to store the list? - ports = app.data.comPorts - if msg["data"]["isMobile"]: - page = render_template( - "settings_mobile.html", - title="Maslow Settings", - settings=setValues, - ports=ports, - pageID="maslowSettings", - ) - else: - page = render_template( - "settings.html", - title="Maslow Settings", - settings=setValues, - ports=ports, - pageID="maslowSettings", - ) - socketio.emit( - "activateModal", - {"title": "Maslow Settings", "message": page}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "advancedSettings": - setValues = app.data.config.getJSONSettingSection("Advanced Settings") - if msg["data"]["isMobile"]: - page = render_template( - "settings_mobile.html", - title="Advanced Settings", - settings=setValues, - pageID="advancedSettings", - ) - else: - page = render_template( - "settings.html", - title="Advanced Settings", - settings=setValues, - pageID="advancedSettings", - ) - socketio.emit( - "activateModal", - {"title": "Advanced Settings", "message": page}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "webControlSettings": - setValues = app.data.config.getJSONSettingSection("WebControl Settings") - if msg["data"]["isMobile"]: - page = render_template( - "settings_mobile.html", - title="WebControl Settings", - settings=setValues, - pageID="webControlSettings", - ) - else: - page = render_template( - "settings.html", - title="WebControl Settings", - settings=setValues, - pageID="webControlSettings", - ) - socketio.emit( - "activateModal", - {"title": "WebControl Settings", "message": page}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "openGCode": - lastSelectedFile = app.data.config.getValue("Maslow Settings", "openFile") - files = [f for f in listdir("gcode") if isfile(join("gcode", f))] - page = render_template( - "openGCode.html", files=files, lastSelectedFile=lastSelectedFile - ) - socketio.emit( - "activateModal", {"title": "GCode", "message": page}, namespace="/MaslowCNC" - ) - elif msg["data"]["page"] == "uploadGCode": - validExtensions = app.data.config.getValue( - "WebControl Settings", "validExtensions" - ) - page = render_template("uploadGCode.html", validExtensions=validExtensions) - socketio.emit( - "activateModal", {"title": "GCode", "message": page}, namespace="/MaslowCNC" - ) - elif msg["data"]["page"] == "importGCini": - page = render_template("importFile.html") - socketio.emit( - "activateModal", - {"title": "Import File", "message": page}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "actions": - page = render_template("actions.html") - socketio.emit( - "activateModal", - {"title": "Actions", "message": page}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "zAxis": - page = render_template("zaxis.html") - socketio.emit( - "activateModal", - {"title": "Z-Axis", "message": page}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "setSprockets": - page = render_template("setSprockets.html") - socketio.emit( - "activateModal", - {"title": "Z-Axis", "message": page}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "triangularCalibration": - motorYoffset = app.data.config.getValue("Maslow Settings", "motorOffsetY") - rotationRadius = app.data.config.getValue("Advanced Settings", "rotationRadius") - chainSagCorrection = app.data.config.getValue( - "Advanced Settings", "chainSagCorrection" - ) - page = render_template( - "triangularCalibration.html", - pageID="triangularCalibration", - motorYoffset=motorYoffset, - rotationRadius=rotationRadius, - chainSagCorrection=chainSagCorrection, - ) - socketio.emit( - "activateModal", - {"title": "Triangular Calibration", "message": page}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "opticalCalibration": - page = render_template("opticalCalibration.html", pageID="opticalCalibration") - socketio.emit( - "activateModal", - {"title": "Optical Calibration", "message": page, "mode": "static"}, - namespace="/MaslowCNC", - ) - elif msg["data"]["page"] == "quickConfigure": - motorOffsetY = app.data.config.getValue("Maslow Settings", "motorOffsetY") - rotationRadius = app.data.config.getValue("Advanced Settings", "rotationRadius") - kinematicsType = app.data.config.getValue("Advanced Settings", "kinematicsType") - if kinematicsType != "Quadrilateral": - if abs(float(rotationRadius) - 138.4) < 0.01: - kinematicsType = "Ring" - else: - kinematicsType = "Custom" - motorSpacingX = app.data.config.getValue("Maslow Settings", "motorSpacingX") - chainOverSprocket = app.data.config.getValue( - "Advanced Settings", "chainOverSprocket" - ) - print("MotorOffsetY=" + str(motorOffsetY)) - page = render_template( - "quickConfigure.html", - pageID="quickConfigure", - motorOffsetY=motorOffsetY, - rotationRadius=rotationRadius, - kinematicsType=kinematicsType, - motorSpacingX=motorSpacingX, - chainOverSprocket=chainOverSprocket, - ) - socketio.emit( - "activateModal", - {"title": "Quick Configure", "message": page}, + app.data.logger.resetIdler() + app.data.console_queue.put(request.sid) + client = request.sid + try: + page, title, isStatic, modalSize, modalType, resume = app.webPageProcessor.createWebPage(msg["data"]["page"],msg["data"]["isMobile"], msg["data"]["args"]) + #if msg["data"]["page"] != "help": + # client = "all" + data = json.dumps({"title": title, "message": page, "isStatic": isStatic, "modalSize": modalSize, "modalType": modalType, "resume":resume, "client":client}) + socketio.emit("message", {"command": "activateModal", "data": data, "dataFormat": "json"}, namespace="/MaslowCNC", ) - + except Exception as e: + app.data.console_queue.put(e) @socketio.on("connect", namespace="/MaslowCNC") def test_connect(): - print("connected") - print(request.sid) - socketio.emit("my response", {"data": "Connected", "count": 0}) + app.data.console_queue.put("connected") + app.data.console_queue.put(request.sid) + if app.uithread == None: + app.uithread = socketio.start_background_task( + app.UIProcessor.start, current_app._get_current_object() + ) + app.uithread.start() + if not app.data.connectionStatus: + app.data.console_queue.put("Attempting to re-establish connection to controller") + app.data.serialPort.openConnection() + + socketio.emit("my response", {"data": "Connected", "count": 0}) + address = app.data.hostAddress + data = json.dumps({"hostAddress": address}) + print(data) + socketio.emit("message", {"command": "hostAddress", "data": data, "dataFormat":"json"}, namespace="/MaslowCNC",) + if app.data.pyInstallUpdateAvailable: + app.data.ui_queue1.put("Action", "pyinstallUpdate", "on") @socketio.on("disconnect", namespace="/MaslowCNC") def test_disconnect(): - print("Client disconnected") + app.data.console_queue.put("Client disconnected") @socketio.on("action", namespace="/MaslowCNC") def command(msg): - app.data.actions.processAction(msg) - - -@socketio.on("move", namespace="/MaslowCNC") -def move(msg): - if not app.data.actions.move( - msg["data"]["direction"], float(msg["data"]["distToMove"]) - ): - app.data.ui_queue.put("Message: Error with move") - - -@socketio.on("moveZ", namespace="/MaslowCNC") -def moveZ(msg): - if not app.data.actions.moveZ( - msg["data"]["direction"], float(msg["data"]["distToMoveZ"]) - ): - app.data.ui_queue.put("Message: Error with Z-Axis move") - + app.data.logger.resetIdler() + retval = app.data.actions.processAction(msg) + if retval == "Shutdown": + print("Shutting Down") + socketio.stop() + print("Shutdown") + if (retval == "TurnOffRPI"): + print("Turning off RPI") + os.system('sudo poweroff') @socketio.on("settingRequest", namespace="/MaslowCNC") def settingRequest(msg): - # didn't move to actions.. this request is just to send it computed values - if msg["data"] == "units": - units = app.data.config.getValue("Computed Settings", "units") - socketio.emit( - "requestedSetting", - {"setting": msg["data"], "value": units}, - namespace="/MaslowCNC", - ) - if msg["data"] == "distToMove": - distToMove = app.data.config.getValue("Computed Settings", "distToMove") - socketio.emit( - "requestedSetting", - {"setting": msg["data"], "value": distToMove}, - namespace="/MaslowCNC", - ) - if msg["data"] == "unitsZ": - unitsZ = app.data.config.getValue("Computed Settings", "unitsZ") - socketio.emit( - "requestedSetting", - {"setting": msg["data"], "value": unitsZ}, - namespace="/MaslowCNC", - ) - if msg["data"] == "distToMoveZ": - distToMoveZ = app.data.config.getValue("Computed Settings", "distToMoveZ") - socketio.emit( - "requestedSetting", - {"setting": msg["data"], "value": distToMoveZ}, - namespace="/MaslowCNC", - ) - + app.data.logger.resetIdler() + # didn't move to actions.. this request is just to send it computed values.. keeping it here makes it faster than putting it through the UIProcessor + setting, value = app.data.actions.processSettingRequest(msg["data"]["section"], msg["data"]["setting"]) + if setting is not None: + data = json.dumps({"setting": setting, "value": value}) + socketio.emit("message", {"command": "requestedSetting", "data": data, "dataFormat": "json"}, namespace="/MaslowCNC",) @socketio.on("updateSetting", namespace="/MaslowCNC") def updateSetting(msg): + app.data.logger.resetIdler() if not app.data.actions.updateSetting(msg["data"]["setting"], msg["data"]["value"]): - app.data.ui_queue.put("Message: Error updating setting") + app.data.ui_queue1.put("Alert", "Alert", "Error updating setting") @socketio.on("checkForGCodeUpdate", namespace="/MaslowCNC") def checkForGCodeUpdate(msg): + app.data.logger.resetIdler() # this currently doesn't check for updated gcode, it just resends it.. ## the gcode file might change the active units so we need to inform the UI of the change. - units = app.data.config.getValue("Computed Settings", "units") - socketio.emit( - "requestedSetting", {"setting": "units", "value": units}, namespace="/MaslowCNC" - ) - ## send updated gcode to UI - socketio.emit( - "gcodeUpdate", - {"data": json.dumps([ob.__dict__ for ob in app.data.gcodeFile.line])}, - namespace="/MaslowCNC", - ) + app.data.ui_queue1.put("Action", "unitsUpdate", "") + app.data.ui_queue1.put("Action", "gcodeUpdate", "") + +@socketio.on("checkForBoardUpdate", namespace="/MaslowCNC") +def checkForBoardUpdate(msg): + app.data.logger.resetIdler() + # this currently doesn't check for updated board, it just resends it.. + app.data.ui_queue1.put("Action", "boardUpdate", "") + +@socketio.on("connect", namespace="/MaslowCNCLogs") +def log_connect(): + app.data.console_queue.put("connected to log") + app.data.console_queue.put(request.sid) + if app.logstreamerthread == None: + app.logstreamerthread = socketio.start_background_task( + app.LogStreamer.start, current_app._get_current_object() + ) + app.logstreamerthread.start() + socketio.emit("my response", {"data": "Connected", "count": 0}, namespace="/MaslowCNCLog") -@socketio.on_error_default -def default_error_handler(e): - print(request.event["message"]) # "my error event" - print(request.event["args"]) # (data,)1 +@socketio.on("disconnect", namespace="/MaslowCNCLogs") +def log_disconnect(): + app.data.console_queue.put("Client disconnected") + + +@app.template_filter('isnumber') +def isnumber(s): + try: + float(s) + return True + except ValueError: + return False + +#def shutdown(): +# print("Shutdown") if __name__ == "__main__": app.debug = False app.config["SECRET_KEY"] = "secret!" - socketio.run(app, use_reloader=False, host="0.0.0.0") + #look for touched file + app.data.config.checkForTouchedPort() + webPort = app.data.config.getValue("WebControl Settings", "webPort") + webPortInt = 5000 + try: + webPortInt = int(webPort) + if webPortInt < 0 or webPortInt > 65535: + webPortInt = 5000 + except Exception as e: + app.data.console_queue.put(e) + app.data.console_queue.put("Invalid port assignment found in webcontrol.json") + + print("-$$$$$-") + print(os.path.abspath(__file__)) + app.data.releaseManager.processAbsolutePath(os.path.abspath(__file__)) + print("-$$$$$-") + + + print("opening browser") + webPortStr = str(webPortInt) + webbrowser.open_new_tab("http://localhost:"+webPortStr) + host_name = socket.gethostname() + host_ip = socket.gethostbyname(host_name) + app.data.hostAddress = host_ip + ":" + webPortStr + + app.data.GPIOButtonService = app.data.config.getValue("Maslow Settings","MaslowButtonService") + # start button service next to last + if (app.data.GPIOButtonService): + print("starting Maslow GPIO button service") + subprocess.run('/usr/local/etc/MBstart.sh') # MB is short for MaslowButon + + #app.data.shutdown = shutdown + socketio.run(app, use_reloader=False, host="0.0.0.0", port=webPortInt) # socketio.run(app, host='0.0.0.0') + diff --git a/main.spec b/main.spec new file mode 100644 index 00000000..98fdadba --- /dev/null +++ b/main.spec @@ -0,0 +1,33 @@ +# -*- mode: python ; coding: utf-8 -*- + +block_cipher = None + +a = Analysis(['main.py'], + pathex=['C:\\Windows\\System32\\downlevel', 'C:\\Users\\john\\PycharmProjects\\WebControl', 'C:\\Users\\jhoga\\Documents\\GitHub\\WebControl'], + binaries=[], + datas=[('templates', 'templates'), ('firmware','firmware'), ('static', 'static'), ('tools', 'tools'), ('docs', 'docs'), ('defaultwebcontrol.json', '.')], + hiddenimports=['flask', 'flask-misaka', 'clr', 'gevent', 'gevent-websocket', 'engineio.async_gevent', 'psutil', 'distro', 'markdown', 'markdown.extensions.fenced_code'], + hookspath=[], + runtime_hooks=[], + excludes=[], + win_no_prefer_redirects=False, + win_private_assemblies=False, + cipher=block_cipher, + noarchive=False) +pyz = PYZ(a.pure, a.zipped_data, + cipher=block_cipher) +exe = EXE(pyz, + a.scripts, + a.binaries, + a.zipfiles, + a.datas, + [], + name='main', + debug=False, + bootloader_ignore_signals=False, + strip=False, + upx=True, + upx_exclude=[], + runtime_tmpdir=None, + console=True, + icon = 'webcontrolicon_256px.ico') diff --git a/requirements.txt b/requirements.txt index 17d33d5d..72299644 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1,19 +1,26 @@ Click==7.0 Flask==1.0.2 +Flask-Misaka Flask-Mobility==0.1.1 Flask-SocketIO==3.0.2 gevent==1.3.7 greenlet==0.4.15 -imutils==0.5.1 itsdangerous==0.24 -Jinja2==2.10 +Jinja2>=2.10.1 MarkupSafe==1.0 -numpy==1.15.2 +numpy==1.16.2 +scipy==1.3.1 opencv-python==3.4.3.18 pyserial==3.4 python-engineio==2.3.2 python-socketio==2.0.0 schedule==0.5.0 -scipy==1.1.0 six==1.11.0 Werkzeug==0.14.1 +psutil +gpiozero +PyGithub +wget +distro +python-frontmatter +markdown \ No newline at end of file diff --git a/scripts/socket.io.slim.js b/scripts/socket.io.slim.js deleted file mode 100644 index c974c898..00000000 --- a/scripts/socket.io.slim.js +++ /dev/null @@ -1,8 +0,0 @@ -/*! - * Socket.IO v2.1.1 - * (c) 2014-2018 Guillermo Rauch - * Released under the MIT License. - */ -!function(t,e){"object"==typeof exports&&"object"==typeof module?module.exports=e():"function"==typeof define&&define.amd?define([],e):"object"==typeof exports?exports.io=e():t.io=e()}(this,function(){return function(t){function e(n){if(r[n])return r[n].exports;var o=r[n]={exports:{},id:n,loaded:!1};return t[n].call(o.exports,o,o.exports,e),o.loaded=!0,o.exports}var r={};return e.m=t,e.c=r,e.p="",e(0)}([function(t,e,r){"use strict";function n(t,e){"object"===("undefined"==typeof t?"undefined":o(t))&&(e=t,t=void 0),e=e||{};var r,n=i(t),s=n.source,h=n.id,p=n.path,u=c[h]&&p in c[h].nsps,f=e.forceNew||e["force new connection"]||!1===e.multiplex||u;return f?r=a(s,e):(c[h]||(c[h]=a(s,e)),r=c[h]),n.query&&!e.query&&(e.query=n.query),r.socket(n.path,e)}var o="function"==typeof Symbol&&"symbol"==typeof Symbol.iterator?function(t){return typeof t}:function(t){return t&&"function"==typeof Symbol&&t.constructor===Symbol&&t!==Symbol.prototype?"symbol":typeof t},i=r(1),s=r(4),a=r(9);r(3)("socket.io-client");t.exports=e=n;var c=e.managers={};e.protocol=s.protocol,e.connect=n,e.Manager=r(9),e.Socket=r(34)},function(t,e,r){(function(e){"use strict";function n(t,r){var n=t;r=r||e.location,null==t&&(t=r.protocol+"//"+r.host),"string"==typeof t&&("/"===t.charAt(0)&&(t="/"===t.charAt(1)?r.protocol+t:r.host+t),/^(https?|wss?):\/\//.test(t)||(t="undefined"!=typeof r?r.protocol+"//"+t:"https://"+t),n=o(t)),n.port||(/^(http|ws)$/.test(n.protocol)?n.port="80":/^(http|ws)s$/.test(n.protocol)&&(n.port="443")),n.path=n.path||"/";var i=n.host.indexOf(":")!==-1,s=i?"["+n.host+"]":n.host;return n.id=n.protocol+"://"+s+":"+n.port,n.href=n.protocol+"://"+s+(r&&r.port===n.port?"":":"+n.port),n}var o=r(2);r(3)("socket.io-client:url");t.exports=n}).call(e,function(){return this}())},function(t,e){var r=/^(?:(?![^:@]+:[^:@\/]*@)(http|https|ws|wss):\/\/)?((?:(([^:@]*)(?::([^:@]*))?)?@)?((?:[a-f0-9]{0,4}:){2,7}[a-f0-9]{0,4}|[^:\/?#]*)(?::(\d*))?)(((\/(?:[^?#](?![^?#\/]*\.[^?#\/.]+(?:[?#]|$)))*\/?)?([^?#\/]*))(?:\?([^#]*))?(?:#(.*))?)/,n=["source","protocol","authority","userInfo","user","password","host","port","relative","path","directory","file","query","anchor"];t.exports=function(t){var e=t,o=t.indexOf("["),i=t.indexOf("]");o!=-1&&i!=-1&&(t=t.substring(0,o)+t.substring(o,i).replace(/:/g,";")+t.substring(i,t.length));for(var s=r.exec(t||""),a={},c=14;c--;)a[n[c]]=s[c]||"";return o!=-1&&i!=-1&&(a.source=e,a.host=a.host.substring(1,a.host.length-1).replace(/;/g,":"),a.authority=a.authority.replace("[","").replace("]","").replace(/;/g,":"),a.ipv6uri=!0),a}},function(t,e){"use strict";t.exports=function(){return function(){}}},function(t,e,r){function n(){}function o(t){var r=""+t.type;if(e.BINARY_EVENT!==t.type&&e.BINARY_ACK!==t.type||(r+=t.attachments+"-"),t.nsp&&"/"!==t.nsp&&(r+=t.nsp+","),null!=t.id&&(r+=t.id),null!=t.data){var n=i(t.data);if(n===!1)return m;r+=n}return r}function i(t){try{return JSON.stringify(t)}catch(t){return!1}}function s(t,e){function r(t){var r=l.deconstructPacket(t),n=o(r.packet),i=r.buffers;i.unshift(n),e(i)}l.removeBlobs(t,r)}function a(){this.reconstructor=null}function c(t){var r=0,n={type:Number(t.charAt(0))};if(null==e.types[n.type])return u("unknown packet type "+n.type);if(e.BINARY_EVENT===n.type||e.BINARY_ACK===n.type){for(var o="";"-"!==t.charAt(++r)&&(o+=t.charAt(r),r!=t.length););if(o!=Number(o)||"-"!==t.charAt(r))throw new Error("Illegal attachments");n.attachments=Number(o)}if("/"===t.charAt(r+1))for(n.nsp="";++r;){var i=t.charAt(r);if(","===i)break;if(n.nsp+=i,r===t.length)break}else n.nsp="/";var s=t.charAt(r+1);if(""!==s&&Number(s)==s){for(n.id="";++r;){var i=t.charAt(r);if(null==i||Number(i)!=i){--r;break}if(n.id+=t.charAt(r),r===t.length)break}n.id=Number(n.id)}if(t.charAt(++r)){var a=h(t.substr(r)),c=a!==!1&&(n.type===e.ERROR||d(a));if(!c)return u("invalid payload");n.data=a}return n}function h(t){try{return JSON.parse(t)}catch(t){return!1}}function p(t){this.reconPack=t,this.buffers=[]}function u(t){return{type:e.ERROR,data:"parser error: "+t}}var f=(r(3)("socket.io-parser"),r(5)),l=r(6),d=r(7),y=r(8);e.protocol=4,e.types=["CONNECT","DISCONNECT","EVENT","ACK","ERROR","BINARY_EVENT","BINARY_ACK"],e.CONNECT=0,e.DISCONNECT=1,e.EVENT=2,e.ACK=3,e.ERROR=4,e.BINARY_EVENT=5,e.BINARY_ACK=6,e.Encoder=n,e.Decoder=a;var m=e.ERROR+'"encode error"';n.prototype.encode=function(t,r){if(e.BINARY_EVENT===t.type||e.BINARY_ACK===t.type)s(t,r);else{var n=o(t);r([n])}},f(a.prototype),a.prototype.add=function(t){var r;if("string"==typeof t)r=c(t),e.BINARY_EVENT===r.type||e.BINARY_ACK===r.type?(this.reconstructor=new p(r),0===this.reconstructor.reconPack.attachments&&this.emit("decoded",r)):this.emit("decoded",r);else{if(!y(t)&&!t.base64)throw new Error("Unknown type: "+t);if(!this.reconstructor)throw new Error("got binary data when not reconstructing a packet");r=this.reconstructor.takeBinaryData(t),r&&(this.reconstructor=null,this.emit("decoded",r))}},a.prototype.destroy=function(){this.reconstructor&&this.reconstructor.finishedReconstruction()},p.prototype.takeBinaryData=function(t){if(this.buffers.push(t),this.buffers.length===this.reconPack.attachments){var e=l.reconstructPacket(this.reconPack,this.buffers);return this.finishedReconstruction(),e}return null},p.prototype.finishedReconstruction=function(){this.reconPack=null,this.buffers=[]}},function(t,e,r){function n(t){if(t)return o(t)}function o(t){for(var e in n.prototype)t[e]=n.prototype[e];return t}t.exports=n,n.prototype.on=n.prototype.addEventListener=function(t,e){return this._callbacks=this._callbacks||{},(this._callbacks["$"+t]=this._callbacks["$"+t]||[]).push(e),this},n.prototype.once=function(t,e){function r(){this.off(t,r),e.apply(this,arguments)}return r.fn=e,this.on(t,r),this},n.prototype.off=n.prototype.removeListener=n.prototype.removeAllListeners=n.prototype.removeEventListener=function(t,e){if(this._callbacks=this._callbacks||{},0==arguments.length)return this._callbacks={},this;var r=this._callbacks["$"+t];if(!r)return this;if(1==arguments.length)return delete this._callbacks["$"+t],this;for(var n,o=0;o0&&!this.encoding){var t=this.packetBuffer.shift();this.packet(t)}},n.prototype.cleanup=function(){for(var t=this.subs.length,e=0;e=this._reconnectionAttempts)this.backoff.reset(),this.emitAll("reconnect_failed"),this.reconnecting=!1;else{var e=this.backoff.duration();this.reconnecting=!0;var r=setTimeout(function(){t.skipReconnect||(t.emitAll("reconnect_attempt",t.backoff.attempts),t.emitAll("reconnecting",t.backoff.attempts),t.skipReconnect||t.open(function(e){e?(t.reconnecting=!1,t.reconnect(),t.emitAll("reconnect_error",e.data)):t.onreconnect()}))},e);this.subs.push({destroy:function(){clearTimeout(r)}})}},n.prototype.onreconnect=function(){var t=this.backoff.attempts;this.reconnecting=!1,this.backoff.reset(),this.updateSocketIds(),this.emitAll("reconnect",t)}},function(t,e,r){t.exports=r(11),t.exports.parser=r(18)},function(t,e,r){(function(e){function n(t,r){if(!(this instanceof n))return new n(t,r);r=r||{},t&&"object"==typeof t&&(r=t,t=null),t?(t=h(t),r.hostname=t.host,r.secure="https"===t.protocol||"wss"===t.protocol,r.port=t.port,t.query&&(r.query=t.query)):r.host&&(r.hostname=h(r.host).host),this.secure=null!=r.secure?r.secure:e.location&&"https:"===location.protocol,r.hostname&&!r.port&&(r.port=this.secure?"443":"80"),this.agent=r.agent||!1,this.hostname=r.hostname||(e.location?location.hostname:"localhost"),this.port=r.port||(e.location&&location.port?location.port:this.secure?443:80),this.query=r.query||{},"string"==typeof this.query&&(this.query=p.decode(this.query)),this.upgrade=!1!==r.upgrade,this.path=(r.path||"/engine.io").replace(/\/$/,"")+"/",this.forceJSONP=!!r.forceJSONP,this.jsonp=!1!==r.jsonp,this.forceBase64=!!r.forceBase64,this.enablesXDR=!!r.enablesXDR,this.timestampParam=r.timestampParam||"t",this.timestampRequests=r.timestampRequests,this.transports=r.transports||["polling","websocket"],this.transportOptions=r.transportOptions||{},this.readyState="",this.writeBuffer=[],this.prevBufferLen=0,this.policyPort=r.policyPort||843,this.rememberUpgrade=r.rememberUpgrade||!1,this.binaryType=null,this.onlyBinaryUpgrades=r.onlyBinaryUpgrades,this.perMessageDeflate=!1!==r.perMessageDeflate&&(r.perMessageDeflate||{}),!0===this.perMessageDeflate&&(this.perMessageDeflate={}),this.perMessageDeflate&&null==this.perMessageDeflate.threshold&&(this.perMessageDeflate.threshold=1024),this.pfx=r.pfx||null,this.key=r.key||null,this.passphrase=r.passphrase||null,this.cert=r.cert||null,this.ca=r.ca||null,this.ciphers=r.ciphers||null,this.rejectUnauthorized=void 0===r.rejectUnauthorized||r.rejectUnauthorized,this.forceNode=!!r.forceNode;var o="object"==typeof e&&e;o.global===o&&(r.extraHeaders&&Object.keys(r.extraHeaders).length>0&&(this.extraHeaders=r.extraHeaders),r.localAddress&&(this.localAddress=r.localAddress)),this.id=null,this.upgrades=null,this.pingInterval=null,this.pingTimeout=null,this.pingIntervalTimer=null,this.pingTimeoutTimer=null,this.open()}function o(t){var e={};for(var r in t)t.hasOwnProperty(r)&&(e[r]=t[r]);return e}var i=r(12),s=r(5),a=(r(3)("engine.io-client:socket"),r(33)),c=r(18),h=r(2),p=r(27);t.exports=n,n.priorWebsocketSuccess=!1,s(n.prototype),n.protocol=c.protocol,n.Socket=n,n.Transport=r(17),n.transports=r(12),n.parser=r(18),n.prototype.createTransport=function(t){var e=o(this.query);e.EIO=c.protocol,e.transport=t;var r=this.transportOptions[t]||{};this.id&&(e.sid=this.id);var n=new i[t]({query:e,socket:this,agent:r.agent||this.agent,hostname:r.hostname||this.hostname,port:r.port||this.port,secure:r.secure||this.secure,path:r.path||this.path,forceJSONP:r.forceJSONP||this.forceJSONP,jsonp:r.jsonp||this.jsonp,forceBase64:r.forceBase64||this.forceBase64,enablesXDR:r.enablesXDR||this.enablesXDR,timestampRequests:r.timestampRequests||this.timestampRequests,timestampParam:r.timestampParam||this.timestampParam,policyPort:r.policyPort||this.policyPort,pfx:r.pfx||this.pfx,key:r.key||this.key,passphrase:r.passphrase||this.passphrase,cert:r.cert||this.cert,ca:r.ca||this.ca,ciphers:r.ciphers||this.ciphers,rejectUnauthorized:r.rejectUnauthorized||this.rejectUnauthorized,perMessageDeflate:r.perMessageDeflate||this.perMessageDeflate,extraHeaders:r.extraHeaders||this.extraHeaders,forceNode:r.forceNode||this.forceNode,localAddress:r.localAddress||this.localAddress,requestTimeout:r.requestTimeout||this.requestTimeout,protocols:r.protocols||void 0});return n},n.prototype.open=function(){var t;if(this.rememberUpgrade&&n.priorWebsocketSuccess&&this.transports.indexOf("websocket")!==-1)t="websocket";else{if(0===this.transports.length){var e=this;return void setTimeout(function(){e.emit("error","No transports available")},0)}t=this.transports[0]}this.readyState="opening";try{t=this.createTransport(t)}catch(t){return this.transports.shift(),void this.open()}t.open(),this.setTransport(t)},n.prototype.setTransport=function(t){var e=this;this.transport&&this.transport.removeAllListeners(),this.transport=t,t.on("drain",function(){e.onDrain()}).on("packet",function(t){e.onPacket(t)}).on("error",function(t){e.onError(t)}).on("close",function(){e.onClose("transport close")})},n.prototype.probe=function(t){function e(){if(u.onlyBinaryUpgrades){var t=!this.supportsBinary&&u.transport.supportsBinary;p=p||t}p||(h.send([{type:"ping",data:"probe"}]),h.once("packet",function(t){if(!p)if("pong"===t.type&&"probe"===t.data){if(u.upgrading=!0,u.emit("upgrading",h),!h)return;n.priorWebsocketSuccess="websocket"===h.name,u.transport.pause(function(){p||"closed"!==u.readyState&&(c(),u.setTransport(h),h.send([{type:"upgrade"}]),u.emit("upgrade",h),h=null,u.upgrading=!1,u.flush())})}else{var e=new Error("probe error");e.transport=h.name,u.emit("upgradeError",e)}}))}function r(){p||(p=!0,c(),h.close(),h=null)}function o(t){var e=new Error("probe error: "+t);e.transport=h.name,r(),u.emit("upgradeError",e)}function i(){o("transport closed")}function s(){o("socket closed")}function a(t){h&&t.name!==h.name&&r()}function c(){h.removeListener("open",e),h.removeListener("error",o),h.removeListener("close",i),u.removeListener("close",s),u.removeListener("upgrading",a)}var h=this.createTransport(t,{probe:1}),p=!1,u=this;n.priorWebsocketSuccess=!1,h.once("open",e),h.once("error",o),h.once("close",i),this.once("close",s),this.once("upgrading",a),h.open()},n.prototype.onOpen=function(){if(this.readyState="open",n.priorWebsocketSuccess="websocket"===this.transport.name,this.emit("open"),this.flush(),"open"===this.readyState&&this.upgrade&&this.transport.pause)for(var t=0,e=this.upgrades.length;t1?{type:b[o],data:t.substring(1)}:{type:b[o]}:k}var i=new Uint8Array(t),o=i[0],s=f(t,1);return w&&"blob"===r&&(s=new w([s])),{type:b[o],data:s}},e.decodeBase64Packet=function(t,e){var r=b[t.charAt(0)];if(!h)return{type:r,data:{base64:!0,data:t.substr(1)}};var n=h.decode(t.substr(1));return"blob"===e&&w&&(n=new w([n])),{type:r,data:n}},e.encodePayload=function(t,r,n){function o(t){return t.length+":"+t}function i(t,n){e.encodePacket(t,!!s&&r,!1,function(t){n(null,o(t))})}"function"==typeof r&&(n=r,r=null);var s=u(t);return r&&s?w&&!g?e.encodePayloadAsBlob(t,n):e.encodePayloadAsArrayBuffer(t,n):t.length?void c(t,i,function(t,e){return n(e.join(""))}):n("0:")},e.decodePayload=function(t,r,n){if("string"!=typeof t)return e.decodePayloadAsBinary(t,r,n);"function"==typeof r&&(n=r,r=null);var o;if(""===t)return n(k,0,1);for(var i,s,a="",c=0,h=t.length;c0;){for(var s=new Uint8Array(o),a=0===s[0],c="",h=1;255!==s[h];h++){if(c.length>310)return n(k,0,1);c+=s[h]}o=f(o,2+c.length),c=parseInt(c);var p=f(o,0,c);if(a)try{p=String.fromCharCode.apply(null,new Uint8Array(p))}catch(t){var u=new Uint8Array(p);p="";for(var h=0;hn&&(r=n),e>=n||e>=r||0===n)return new ArrayBuffer(0);for(var o=new Uint8Array(t),i=new Uint8Array(r-e),s=e,a=0;s=55296&&e<=56319&&o65535&&(e-=65536,o+=k(e>>>10&1023|55296),e=56320|1023&e),o+=k(e);return o}function c(t,e){if(t>=55296&&t<=57343){if(e)throw Error("Lone surrogate U+"+t.toString(16).toUpperCase()+" is not a scalar value");return!1}return!0}function h(t,e){return k(t>>e&63|128)}function p(t,e){if(0==(4294967168&t))return k(t);var r="";return 0==(4294965248&t)?r=k(t>>6&31|192):0==(4294901760&t)?(c(t,e)||(t=65533),r=k(t>>12&15|224),r+=h(t,6)):0==(4292870144&t)&&(r=k(t>>18&7|240),r+=h(t,12),r+=h(t,6)),r+=k(63&t|128)}function u(t,e){e=e||{};for(var r,n=!1!==e.strict,o=s(t),i=o.length,a=-1,c="";++a=v)throw Error("Invalid byte index");var t=255&g[b];if(b++,128==(192&t))return 63&t;throw Error("Invalid continuation byte")}function l(t){var e,r,n,o,i;if(b>v)throw Error("Invalid byte index");if(b==v)return!1;if(e=255&g[b],b++,0==(128&e))return e;if(192==(224&e)){if(r=f(),i=(31&e)<<6|r,i>=128)return i;throw Error("Invalid continuation byte")}if(224==(240&e)){if(r=f(),n=f(),i=(15&e)<<12|r<<6|n,i>=2048)return c(i,t)?i:65533;throw Error("Invalid continuation byte")}if(240==(248&e)&&(r=f(),n=f(),o=f(),i=(7&e)<<18|r<<12|n<<6|o,i>=65536&&i<=1114111))return i;throw Error("Invalid UTF-8 detected")}function d(t,e){e=e||{};var r=!1!==e.strict;g=s(t),v=g.length,b=0;for(var n,o=[];(n=l(r))!==!1;)o.push(n);return a(o)}var y="object"==typeof e&&e,m=("object"==typeof t&&t&&t.exports==y&&t,"object"==typeof o&&o);m.global!==m&&m.window!==m||(i=m);var g,v,b,k=String.fromCharCode,w={version:"2.1.2",encode:u,decode:d};n=function(){return w}.call(e,r,e,t),!(void 0!==n&&(t.exports=n))}(this)}).call(e,r(24)(t),function(){return this}())},function(t,e){t.exports=function(t){return t.webpackPolyfill||(t.deprecate=function(){},t.paths=[],t.children=[],t.webpackPolyfill=1),t}},function(t,e){!function(){"use strict";for(var t="ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/",r=new Uint8Array(256),n=0;n>2],i+=t[(3&n[r])<<4|n[r+1]>>4],i+=t[(15&n[r+1])<<2|n[r+2]>>6],i+=t[63&n[r+2]];return o%3===2?i=i.substring(0,i.length-1)+"=":o%3===1&&(i=i.substring(0,i.length-2)+"=="),i},e.decode=function(t){var e,n,o,i,s,a=.75*t.length,c=t.length,h=0;"="===t[t.length-1]&&(a--,"="===t[t.length-2]&&a--);var p=new ArrayBuffer(a),u=new Uint8Array(p);for(e=0;e>4,u[h++]=(15&o)<<4|i>>2,u[h++]=(3&i)<<6|63&s;return p}}()},function(t,e){(function(e){function r(t){for(var e=0;e0);return e}function n(t){var e=0;for(p=0;p';i=document.createElement(t)}catch(t){i=document.createElement("iframe"),i.name=o.iframeId,i.src="javascript:0"}i.id=o.iframeId,o.form.appendChild(i),o.iframe=i}var o=this;if(!this.form){var i,s=document.createElement("form"),a=document.createElement("textarea"),p=this.iframeId="eio_iframe_"+this.index;s.className="socketio",s.style.position="absolute",s.style.top="-1000px",s.style.left="-1000px",s.target=p,s.method="POST",s.setAttribute("accept-charset","utf-8"),a.name="d",s.appendChild(a),document.body.appendChild(s),this.form=s,this.area=a}this.form.action=this.uri(),n(),t=t.replace(h,"\\\n"),this.area.value=t.replace(c,"\\n");try{this.form.submit()}catch(t){}this.iframe.attachEvent?this.iframe.onreadystatechange=function(){"complete"===o.iframe.readyState&&r()}:this.iframe.onload=r}}).call(e,function(){return this}())},function(t,e,r){(function(e){function n(t){var e=t&&t.forceBase64;e&&(this.supportsBinary=!1),this.perMessageDeflate=t.perMessageDeflate,this.usingBrowserWebSocket=p&&!t.forceNode,this.protocols=t.protocols,this.usingBrowserWebSocket||(u=o),i.call(this,t)}var o,i=r(17),s=r(18),a=r(27),c=r(28),h=r(29),p=(r(3)("engine.io-client:websocket"),e.WebSocket||e.MozWebSocket);if("undefined"==typeof window)try{o=r(32)}catch(t){}var u=p;u||"undefined"!=typeof window||(u=o),t.exports=n,c(n,i),n.prototype.name="websocket",n.prototype.supportsBinary=!0,n.prototype.doOpen=function(){if(this.check()){var t=this.uri(),e=this.protocols,r={agent:this.agent,perMessageDeflate:this.perMessageDeflate};r.pfx=this.pfx,r.key=this.key,r.passphrase=this.passphrase,r.cert=this.cert,r.ca=this.ca,r.ciphers=this.ciphers,r.rejectUnauthorized=this.rejectUnauthorized,this.extraHeaders&&(r.headers=this.extraHeaders),this.localAddress&&(r.localAddress=this.localAddress);try{this.ws=this.usingBrowserWebSocket?e?new u(t,e):new u(t):new u(t,e,r)}catch(t){return this.emit("error",t)}void 0===this.ws.binaryType&&(this.supportsBinary=!1),this.ws.supports&&this.ws.supports.binary?(this.supportsBinary=!0,this.ws.binaryType="nodebuffer"):this.ws.binaryType="arraybuffer",this.addEventListeners()}},n.prototype.addEventListeners=function(){var t=this;this.ws.onopen=function(){t.onOpen()},this.ws.onclose=function(){t.onClose()},this.ws.onmessage=function(e){t.onData(e.data)},this.ws.onerror=function(e){t.onError("websocket error",e)}},n.prototype.write=function(t){function r(){n.emit("flush"),setTimeout(function(){n.writable=!0,n.emit("drain")},0)}var n=this;this.writable=!1;for(var o=t.length,i=0,a=o;i0&&t.jitter<=1?t.jitter:0,this.attempts=0}t.exports=r,r.prototype.duration=function(){var t=this.ms*Math.pow(this.factor,this.attempts++);if(this.jitter){var e=Math.random(),r=Math.floor(e*this.jitter*t);t=0==(1&Math.floor(10*e))?t-r:t+r}return 0|Math.min(t,this.max)},r.prototype.reset=function(){this.attempts=0},r.prototype.setMin=function(t){this.ms=t},r.prototype.setMax=function(t){this.max=t},r.prototype.setJitter=function(t){this.jitter=t}}])}); -//# sourceMappingURL=socket.io.slim.js.map diff --git a/settings/settings.py b/settings/settings.py index af618b1c..75db5ba5 100644 --- a/settings/settings.py +++ b/settings/settings.py @@ -112,6 +112,27 @@ "default": 3.17, "firmwareKey": 19, }, + { + "type": "bool", + "title": "Wii Pendant Installed", + "desc": "Wii controller connected via Bluetooth", + "key": "wiiPendantPresent", + "default": 0, + }, + { + "type": "bool", + "title": "Raspberry Pi Button Service Active", + "desc": "GPIO buttons run in separate process / system service", + "key": "MaslowButtonService", + "default": 0, + }, + { + "type": "bool", + "title": "RPI Text display", + "desc": "Attached command line text display on Maslow", + "key": "clidisplay", + "default": 0, + }, { "type": "options", "title": "Color Scheme", diff --git a/site-packages.spec b/site-packages.spec new file mode 100644 index 00000000..ccab03e9 --- /dev/null +++ b/site-packages.spec @@ -0,0 +1,36 @@ +# -*- mode: python -*- + +block_cipher = None + + +a = Analysis(['.venv\\lib\\site-packages', 'main.py'], + pathex=['', 'C:\\Users\\john\\PycharmProjects\\WebControl'], + binaries=[], + datas=[], + hiddenimports=[], + hookspath=[], + runtime_hooks=[], + excludes=[], + win_no_prefer_redirects=False, + win_private_assemblies=False, + cipher=block_cipher, + noarchive=False) +pyz = PYZ(a.pure, a.zipped_data, + cipher=block_cipher) +exe = EXE(pyz, + a.scripts, + [], + exclude_binaries=True, + name='site-packages', + debug=False, + bootloader_ignore_signals=False, + strip=False, + upx=True, + console=True ) +coll = COLLECT(exe, + a.binaries, + a.zipfiles, + a.datas, + strip=False, + upx=True, + name='site-packages') diff --git a/static/favicon.ico b/static/favicon.ico new file mode 100644 index 00000000..ac0183a4 Binary files /dev/null and b/static/favicon.ico differ diff --git a/static/images/GPIO/RPI_pin_layout.svg b/static/images/GPIO/RPI_pin_layout.svg new file mode 100644 index 00000000..84e0ff2b --- /dev/null +++ b/static/images/GPIO/RPI_pin_layout.svg @@ -0,0 +1,2777 @@ + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + + + 3V3Power + + + + GPIO2SDA I²C + + + + GPIO3SCL I²C + + + + GPIO4 + + + + Ground + + + + GPIO17 + + + + GPIO27 + + + + GPIO22 + + + + 3V3Power + + + + GPIO10SPI MOSI + + + + GPIO9SPI MISO + + + + GPIO11SPI SCLK + + + Ground + + + + ID SDI²C ID + + + + GPIO5 + + + + GPIO6 + + + + GPIO13 + + + + GPIO19 + + + + GPIO26 + + + + Ground + + + + 5VPower + + + + 5VPower + + + + Ground + + + + GPIO14UART0 TXD + + + + GPIO15UART0 RXD + + + + GPIO18 + + + + Ground + + + + GPIO23 + + + + GPIO24 + + + + Ground + + + + GPIO25 + + + + GPIO8SPI CE0 + + + + GPIO7SPI CE1 + + + + ID SCI²C ID + + + + Ground + + + + GPIO12 + + + + Ground + + + + GPIO16 + + + + GPIO20 + + + + GPIO21 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + All Models + 40-pinmodels only + 1 + 1 + 3 + 5 + 7 + 9 + 11 + 13 + 15 + 17 + 19 + 21 + 23 + 25 + 27 + 29 + 31 + 33 + 35 + 37 + 39 + 2 + 4 + 6 + 8 + 10 + 12 + 14 + 16 + 18 + 20 + 22 + 24 + 26 + 28 + 30 + 32 + 34 + 36 + 38 + 40 + USB Ports + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/static/images/gettingStarted/Sprocket at 12-00.png b/static/images/gettingStarted/Sprocket at 12-00.png new file mode 100644 index 00000000..4bde7e94 Binary files /dev/null and b/static/images/gettingStarted/Sprocket at 12-00.png differ diff --git a/static/images/gettingStarted/chainOffSprocketsBottom.png b/static/images/gettingStarted/chainOffSprocketsBottom.png new file mode 100644 index 00000000..66dca318 Binary files /dev/null and b/static/images/gettingStarted/chainOffSprocketsBottom.png differ diff --git a/static/images/gettingStarted/chainOffSprocketsTop.png b/static/images/gettingStarted/chainOffSprocketsTop.png new file mode 100644 index 00000000..33cadccd Binary files /dev/null and b/static/images/gettingStarted/chainOffSprocketsTop.png differ diff --git a/static/images/gettingStarted/comPort.png b/static/images/gettingStarted/comPort.png new file mode 100644 index 00000000..dcd38a6e Binary files /dev/null and b/static/images/gettingStarted/comPort.png differ diff --git a/static/images/gettingStarted/extendChainDistance.png b/static/images/gettingStarted/extendChainDistance.png new file mode 100644 index 00000000..1d50a8cf Binary files /dev/null and b/static/images/gettingStarted/extendChainDistance.png differ diff --git a/static/images/holeyCalibration/holeyCalibration.png b/static/images/holeyCalibration/holeyCalibration.png new file mode 100644 index 00000000..18163b60 Binary files /dev/null and b/static/images/holeyCalibration/holeyCalibration.png differ diff --git a/static/images/quickConfig/linkage.png b/static/images/quickConfig/linkage.png new file mode 100644 index 00000000..6f8c650d Binary files /dev/null and b/static/images/quickConfig/linkage.png differ diff --git a/static/images/quickConfig/measureCenterMotor.png b/static/images/quickConfig/measureCenterMotor.png new file mode 100644 index 00000000..f6add214 Binary files /dev/null and b/static/images/quickConfig/measureCenterMotor.png differ diff --git a/static/images/quickConfig/measureEdgeMotor.png b/static/images/quickConfig/measureEdgeMotor.png new file mode 100644 index 00000000..83d9556e Binary files /dev/null and b/static/images/quickConfig/measureEdgeMotor.png differ diff --git a/static/images/quickConfig/metalMaslow.png b/static/images/quickConfig/metalMaslow.png new file mode 100644 index 00000000..d0d89611 Binary files /dev/null and b/static/images/quickConfig/metalMaslow.png differ diff --git a/static/images/quickConfig/motorOffsetY.png b/static/images/quickConfig/motorOffsetY.png new file mode 100644 index 00000000..a9db3693 Binary files /dev/null and b/static/images/quickConfig/motorOffsetY.png differ diff --git a/static/images/quickConfig/pantograph.png b/static/images/quickConfig/pantograph.png new file mode 100644 index 00000000..8c7fc359 Binary files /dev/null and b/static/images/quickConfig/pantograph.png differ diff --git a/static/images/quickConfig/quadrilateral.png b/static/images/quickConfig/quadrilateral.png new file mode 100644 index 00000000..e2d96ccb Binary files /dev/null and b/static/images/quickConfig/quadrilateral.png differ diff --git a/static/images/quickConfig/ring.png b/static/images/quickConfig/ring.png new file mode 100644 index 00000000..1ae75bf0 Binary files /dev/null and b/static/images/quickConfig/ring.png differ diff --git a/static/images/triangularCalibration/triangularCalibration.png b/static/images/triangularCalibration/triangularCalibration.png new file mode 100644 index 00000000..7bc4ea70 Binary files /dev/null and b/static/images/triangularCalibration/triangularCalibration.png differ diff --git a/static/scripts/ace.js b/static/scripts/ace.js new file mode 100644 index 00000000..a8416404 --- /dev/null +++ b/static/scripts/ace.js @@ -0,0 +1,16 @@ +(function(){function o(n){var i=e;n&&(e[n]||(e[n]={}),i=e[n]);if(!i.define||!i.define.packaged)t.original=i.define,i.define=t,i.define.packaged=!0;if(!i.require||!i.require.packaged)r.original=i.require,i.require=r,i.require.packaged=!0}var ACE_NAMESPACE = "ace",e=function(){return this}();!e&&typeof window!="undefined"&&(e=window);if(!ACE_NAMESPACE&&typeof requirejs!="undefined")return;var t=function(e,n,r){if(typeof e!="string"){t.original?t.original.apply(this,arguments):(console.error("dropping module because define wasn't a string."),console.trace());return}arguments.length==2&&(r=n),t.modules[e]||(t.payloads[e]=r,t.modules[e]=null)};t.modules={},t.payloads={};var n=function(e,t,n){if(typeof t=="string"){var i=s(e,t);if(i!=undefined)return n&&n(),i}else if(Object.prototype.toString.call(t)==="[object Array]"){var o=[];for(var u=0,a=t.length;u1&&u(t,"")>-1&&(a=RegExp(this.source,r.replace.call(o(this),"g","")),r.replace.call(e.slice(t.index),a,function(){for(var e=1;et.index&&this.lastIndex--}return t},s||(RegExp.prototype.test=function(e){var t=r.exec.call(this,e);return t&&this.global&&!t[0].length&&this.lastIndex>t.index&&this.lastIndex--,!!t})}),ace.define("ace/lib/es5-shim",["require","exports","module"],function(e,t,n){function r(){}function w(e){try{return Object.defineProperty(e,"sentinel",{}),"sentinel"in e}catch(t){}}function H(e){return e=+e,e!==e?e=0:e!==0&&e!==1/0&&e!==-1/0&&(e=(e>0||-1)*Math.floor(Math.abs(e))),e}function B(e){var t=typeof e;return e===null||t==="undefined"||t==="boolean"||t==="number"||t==="string"}function j(e){var t,n,r;if(B(e))return e;n=e.valueOf;if(typeof n=="function"){t=n.call(e);if(B(t))return t}r=e.toString;if(typeof r=="function"){t=r.call(e);if(B(t))return t}throw new TypeError}Function.prototype.bind||(Function.prototype.bind=function(t){var n=this;if(typeof n!="function")throw new TypeError("Function.prototype.bind called on incompatible "+n);var i=u.call(arguments,1),s=function(){if(this instanceof s){var e=n.apply(this,i.concat(u.call(arguments)));return Object(e)===e?e:this}return n.apply(t,i.concat(u.call(arguments)))};return n.prototype&&(r.prototype=n.prototype,s.prototype=new r,r.prototype=null),s});var i=Function.prototype.call,s=Array.prototype,o=Object.prototype,u=s.slice,a=i.bind(o.toString),f=i.bind(o.hasOwnProperty),l,c,h,p,d;if(d=f(o,"__defineGetter__"))l=i.bind(o.__defineGetter__),c=i.bind(o.__defineSetter__),h=i.bind(o.__lookupGetter__),p=i.bind(o.__lookupSetter__);if([1,2].splice(0).length!=2)if(!function(){function e(e){var t=new Array(e+2);return t[0]=t[1]=0,t}var t=[],n;t.splice.apply(t,e(20)),t.splice.apply(t,e(26)),n=t.length,t.splice(5,0,"XXX"),n+1==t.length;if(n+1==t.length)return!0}())Array.prototype.splice=function(e,t){var n=this.length;e>0?e>n&&(e=n):e==void 0?e=0:e<0&&(e=Math.max(n+e,0)),e+ta)for(h=l;h--;)this[f+h]=this[a+h];if(s&&e===c)this.length=c,this.push.apply(this,i);else{this.length=c+s;for(h=0;h>>0;if(a(t)!="[object Function]")throw new TypeError;while(++s>>0,s=Array(i),o=arguments[1];if(a(t)!="[object Function]")throw new TypeError(t+" is not a function");for(var u=0;u>>0,s=[],o,u=arguments[1];if(a(t)!="[object Function]")throw new TypeError(t+" is not a function");for(var f=0;f>>0,s=arguments[1];if(a(t)!="[object Function]")throw new TypeError(t+" is not a function");for(var o=0;o>>0,s=arguments[1];if(a(t)!="[object Function]")throw new TypeError(t+" is not a function");for(var o=0;o>>0;if(a(t)!="[object Function]")throw new TypeError(t+" is not a function");if(!i&&arguments.length==1)throw new TypeError("reduce of empty array with no initial value");var s=0,o;if(arguments.length>=2)o=arguments[1];else do{if(s in r){o=r[s++];break}if(++s>=i)throw new TypeError("reduce of empty array with no initial value")}while(!0);for(;s>>0;if(a(t)!="[object Function]")throw new TypeError(t+" is not a function");if(!i&&arguments.length==1)throw new TypeError("reduceRight of empty array with no initial value");var s,o=i-1;if(arguments.length>=2)s=arguments[1];else do{if(o in r){s=r[o--];break}if(--o<0)throw new TypeError("reduceRight of empty array with no initial value")}while(!0);do o in this&&(s=t.call(void 0,s,r[o],o,n));while(o--);return s});if(!Array.prototype.indexOf||[0,1].indexOf(1,2)!=-1)Array.prototype.indexOf=function(t){var n=g&&a(this)=="[object String]"?this.split(""):F(this),r=n.length>>>0;if(!r)return-1;var i=0;arguments.length>1&&(i=H(arguments[1])),i=i>=0?i:Math.max(0,r+i);for(;i>>0;if(!r)return-1;var i=r-1;arguments.length>1&&(i=Math.min(i,H(arguments[1]))),i=i>=0?i:r-Math.abs(i);for(;i>=0;i--)if(i in n&&t===n[i])return i;return-1};Object.getPrototypeOf||(Object.getPrototypeOf=function(t){return t.__proto__||(t.constructor?t.constructor.prototype:o)});if(!Object.getOwnPropertyDescriptor){var y="Object.getOwnPropertyDescriptor called on a non-object: ";Object.getOwnPropertyDescriptor=function(t,n){if(typeof t!="object"&&typeof t!="function"||t===null)throw new TypeError(y+t);if(!f(t,n))return;var r,i,s;r={enumerable:!0,configurable:!0};if(d){var u=t.__proto__;t.__proto__=o;var i=h(t,n),s=p(t,n);t.__proto__=u;if(i||s)return i&&(r.get=i),s&&(r.set=s),r}return r.value=t[n],r}}Object.getOwnPropertyNames||(Object.getOwnPropertyNames=function(t){return Object.keys(t)});if(!Object.create){var b;Object.prototype.__proto__===null?b=function(){return{__proto__:null}}:b=function(){var e={};for(var t in e)e[t]=null;return e.constructor=e.hasOwnProperty=e.propertyIsEnumerable=e.isPrototypeOf=e.toLocaleString=e.toString=e.valueOf=e.__proto__=null,e},Object.create=function(t,n){var r;if(t===null)r=b();else{if(typeof t!="object")throw new TypeError("typeof prototype["+typeof t+"] != 'object'");var i=function(){};i.prototype=t,r=new i,r.__proto__=t}return n!==void 0&&Object.defineProperties(r,n),r}}if(Object.defineProperty){var E=w({}),S=typeof document=="undefined"||w(document.createElement("div"));if(!E||!S)var x=Object.defineProperty}if(!Object.defineProperty||x){var T="Property description must be an object: ",N="Object.defineProperty called on non-object: ",C="getters & setters can not be defined on this javascript engine";Object.defineProperty=function(t,n,r){if(typeof t!="object"&&typeof t!="function"||t===null)throw new TypeError(N+t);if(typeof r!="object"&&typeof r!="function"||r===null)throw new TypeError(T+r);if(x)try{return x.call(Object,t,n,r)}catch(i){}if(f(r,"value"))if(d&&(h(t,n)||p(t,n))){var s=t.__proto__;t.__proto__=o,delete t[n],t[n]=r.value,t.__proto__=s}else t[n]=r.value;else{if(!d)throw new TypeError(C);f(r,"get")&&l(t,n,r.get),f(r,"set")&&c(t,n,r.set)}return t}}Object.defineProperties||(Object.defineProperties=function(t,n){for(var r in n)f(n,r)&&Object.defineProperty(t,r,n[r]);return t}),Object.seal||(Object.seal=function(t){return t}),Object.freeze||(Object.freeze=function(t){return t});try{Object.freeze(function(){})}catch(k){Object.freeze=function(t){return function(n){return typeof n=="function"?n:t(n)}}(Object.freeze)}Object.preventExtensions||(Object.preventExtensions=function(t){return t}),Object.isSealed||(Object.isSealed=function(t){return!1}),Object.isFrozen||(Object.isFrozen=function(t){return!1}),Object.isExtensible||(Object.isExtensible=function(t){if(Object(t)===t)throw new TypeError;var n="";while(f(t,n))n+="?";t[n]=!0;var r=f(t,n);return delete t[n],r});if(!Object.keys){var L=!0,A=["toString","toLocaleString","valueOf","hasOwnProperty","isPrototypeOf","propertyIsEnumerable","constructor"],O=A.length;for(var M in{toString:null})L=!1;Object.keys=function I(e){if(typeof e!="object"&&typeof e!="function"||e===null)throw new TypeError("Object.keys called on a non-object");var I=[];for(var t in e)f(e,t)&&I.push(t);if(L)for(var n=0,r=O;n=0?parseFloat((s.match(/(?:MSIE |Trident\/[0-9]+[\.0-9]+;.*rv:)([0-9]+[\.0-9]+)/)||[])[1]):parseFloat((s.match(/(?:Trident\/[0-9]+[\.0-9]+;.*rv:)([0-9]+[\.0-9]+)/)||[])[1]),t.isOldIE=t.isIE&&t.isIE<9,t.isGecko=t.isMozilla=s.match(/ Gecko\/\d+/),t.isOpera=typeof opera=="object"&&Object.prototype.toString.call(window.opera)=="[object Opera]",t.isWebKit=parseFloat(s.split("WebKit/")[1])||undefined,t.isChrome=parseFloat(s.split(" Chrome/")[1])||undefined,t.isEdge=parseFloat(s.split(" Edge/")[1])||undefined,t.isAIR=s.indexOf("AdobeAIR")>=0,t.isIPad=s.indexOf("iPad")>=0,t.isAndroid=s.indexOf("Android")>=0,t.isChromeOS=s.indexOf(" CrOS ")>=0,t.isIOS=/iPad|iPhone|iPod/.test(s)&&!window.MSStream,t.isIOS&&(t.isMac=!0),t.isMobile=t.isIPad||t.isAndroid}),ace.define("ace/lib/dom",["require","exports","module","ace/lib/useragent"],function(e,t,n){"use strict";var r=e("./useragent"),i="http://www.w3.org/1999/xhtml";t.buildDom=function o(e,t,n){if(typeof e=="string"&&e){var r=document.createTextNode(e);return t&&t.appendChild(r),r}if(!Array.isArray(e))return e;if(typeof e[0]!="string"||!e[0]){var i=[];for(var s=0;s=1.5:!0;if(typeof document!="undefined"){var s=document.createElement("div");t.HI_DPI&&s.style.transform!==undefined&&(t.HAS_CSS_TRANSFORMS=!0),!r.isEdge&&typeof s.style.animationName!="undefined"&&(t.HAS_CSS_ANIMATION=!0),s=null}t.HAS_CSS_TRANSFORMS?t.translate=function(e,t,n){e.style.transform="translate("+Math.round(t)+"px, "+Math.round(n)+"px)"}:t.translate=function(e,t,n){e.style.top=Math.round(n)+"px",e.style.left=Math.round(t)+"px"}}),ace.define("ace/lib/oop",["require","exports","module"],function(e,t,n){"use strict";t.inherits=function(e,t){e.super_=t,e.prototype=Object.create(t.prototype,{constructor:{value:e,enumerable:!1,writable:!0,configurable:!0}})},t.mixin=function(e,t){for(var n in t)e[n]=t[n];return e},t.implement=function(e,n){t.mixin(e,n)}}),ace.define("ace/lib/keys",["require","exports","module","ace/lib/oop"],function(e,t,n){"use strict";var r=e("./oop"),i=function(){var e={MODIFIER_KEYS:{16:"Shift",17:"Ctrl",18:"Alt",224:"Meta"},KEY_MODS:{ctrl:1,alt:2,option:2,shift:4,"super":8,meta:8,command:8,cmd:8},FUNCTION_KEYS:{8:"Backspace",9:"Tab",13:"Return",19:"Pause",27:"Esc",32:"Space",33:"PageUp",34:"PageDown",35:"End",36:"Home",37:"Left",38:"Up",39:"Right",40:"Down",44:"Print",45:"Insert",46:"Delete",96:"Numpad0",97:"Numpad1",98:"Numpad2",99:"Numpad3",100:"Numpad4",101:"Numpad5",102:"Numpad6",103:"Numpad7",104:"Numpad8",105:"Numpad9","-13":"NumpadEnter",112:"F1",113:"F2",114:"F3",115:"F4",116:"F5",117:"F6",118:"F7",119:"F8",120:"F9",121:"F10",122:"F11",123:"F12",144:"Numlock",145:"Scrolllock"},PRINTABLE_KEYS:{32:" ",48:"0",49:"1",50:"2",51:"3",52:"4",53:"5",54:"6",55:"7",56:"8",57:"9",59:";",61:"=",65:"a",66:"b",67:"c",68:"d",69:"e",70:"f",71:"g",72:"h",73:"i",74:"j",75:"k",76:"l",77:"m",78:"n",79:"o",80:"p",81:"q",82:"r",83:"s",84:"t",85:"u",86:"v",87:"w",88:"x",89:"y",90:"z",107:"+",109:"-",110:".",186:";",187:"=",188:",",189:"-",190:".",191:"/",192:"`",219:"[",220:"\\",221:"]",222:"'",111:"/",106:"*"}},t,n;for(n in e.FUNCTION_KEYS)t=e.FUNCTION_KEYS[n].toLowerCase(),e[t]=parseInt(n,10);for(n in e.PRINTABLE_KEYS)t=e.PRINTABLE_KEYS[n].toLowerCase(),e[t]=parseInt(n,10);return r.mixin(e,e.MODIFIER_KEYS),r.mixin(e,e.PRINTABLE_KEYS),r.mixin(e,e.FUNCTION_KEYS),e.enter=e["return"],e.escape=e.esc,e.del=e["delete"],e[173]="-",function(){var t=["cmd","ctrl","alt","shift"];for(var n=Math.pow(2,t.length);n--;)e.KEY_MODS[n]=t.filter(function(t){return n&e.KEY_MODS[t]}).join("-")+"-"}(),e.KEY_MODS[0]="",e.KEY_MODS[-1]="input-",e}();r.mixin(t,i),t.keyCodeToString=function(e){var t=i[e];return typeof t!="string"&&(t=String.fromCharCode(e)),t.toLowerCase()}}),ace.define("ace/lib/event",["require","exports","module","ace/lib/keys","ace/lib/useragent"],function(e,t,n){"use strict";function a(e,t,n){var a=u(t);if(!i.isMac&&s){t.getModifierState&&(t.getModifierState("OS")||t.getModifierState("Win"))&&(a|=8);if(s.altGr){if((3&a)==3)return;s.altGr=0}if(n===18||n===17){var f="location"in t?t.location:t.keyLocation;if(n===17&&f===1)s[n]==1&&(o=t.timeStamp);else if(n===18&&a===3&&f===2){var l=t.timeStamp-o;l<50&&(s.altGr=!0)}}}n in r.MODIFIER_KEYS&&(n=-1),a&8&&n>=91&&n<=93&&(n=-1);if(!a&&n===13){var f="location"in t?t.location:t.keyLocation;if(f===3){e(t,a,-n);if(t.defaultPrevented)return}}if(i.isChromeOS&&a&8){e(t,a,n);if(t.defaultPrevented)return;a&=-9}return!!a||n in r.FUNCTION_KEYS||n in r.PRINTABLE_KEYS?e(t,a,n):!1}function f(){s=Object.create(null)}var r=e("./keys"),i=e("./useragent"),s=null,o=0;t.addListener=function(e,t,n){if(e.addEventListener)return e.addEventListener(t,n,!1);if(e.attachEvent){var r=function(){n.call(e,window.event)};n._wrapper=r,e.attachEvent("on"+t,r)}},t.removeListener=function(e,t,n){if(e.removeEventListener)return e.removeEventListener(t,n,!1);e.detachEvent&&e.detachEvent("on"+t,n._wrapper||n)},t.stopEvent=function(e){return t.stopPropagation(e),t.preventDefault(e),!1},t.stopPropagation=function(e){e.stopPropagation?e.stopPropagation():e.cancelBubble=!0},t.preventDefault=function(e){e.preventDefault?e.preventDefault():e.returnValue=!1},t.getButton=function(e){return e.type=="dblclick"?0:e.type=="contextmenu"||i.isMac&&e.ctrlKey&&!e.altKey&&!e.shiftKey?2:e.preventDefault?e.button:{1:0,2:2,4:1}[e.button]},t.capture=function(e,n,r){function i(e){n&&n(e),r&&r(e),t.removeListener(document,"mousemove",n,!0),t.removeListener(document,"mouseup",i,!0),t.removeListener(document,"dragstart",i,!0)}return t.addListener(document,"mousemove",n,!0),t.addListener(document,"mouseup",i,!0),t.addListener(document,"dragstart",i,!0),i},t.addMouseWheelListener=function(e,n){"onmousewheel"in e?t.addListener(e,"mousewheel",function(e){var t=8;e.wheelDeltaX!==undefined?(e.wheelX=-e.wheelDeltaX/t,e.wheelY=-e.wheelDeltaY/t):(e.wheelX=0,e.wheelY=-e.wheelDelta/t),n(e)}):"onwheel"in e?t.addListener(e,"wheel",function(e){var t=.35;switch(e.deltaMode){case e.DOM_DELTA_PIXEL:e.wheelX=e.deltaX*t||0,e.wheelY=e.deltaY*t||0;break;case e.DOM_DELTA_LINE:case e.DOM_DELTA_PAGE:e.wheelX=(e.deltaX||0)*5,e.wheelY=(e.deltaY||0)*5}n(e)}):t.addListener(e,"DOMMouseScroll",function(e){e.axis&&e.axis==e.HORIZONTAL_AXIS?(e.wheelX=(e.detail||0)*5,e.wheelY=0):(e.wheelX=0,e.wheelY=(e.detail||0)*5),n(e)})},t.addMultiMouseDownListener=function(e,n,r,s){function c(e){t.getButton(e)!==0?o=0:e.detail>1?(o++,o>4&&(o=1)):o=1;if(i.isIE){var c=Math.abs(e.clientX-u)>5||Math.abs(e.clientY-a)>5;if(!f||c)o=1;f&&clearTimeout(f),f=setTimeout(function(){f=null},n[o-1]||600),o==1&&(u=e.clientX,a=e.clientY)}e._clicks=o,r[s]("mousedown",e);if(o>4)o=0;else if(o>1)return r[s](l[o],e)}function h(e){o=2,f&&clearTimeout(f),f=setTimeout(function(){f=null},n[o-1]||600),r[s]("mousedown",e),r[s](l[o],e)}var o=0,u,a,f,l={2:"dblclick",3:"tripleclick",4:"quadclick"};Array.isArray(e)||(e=[e]),e.forEach(function(e){t.addListener(e,"mousedown",c),i.isOldIE&&t.addListener(e,"dblclick",h)})};var u=!i.isMac||!i.isOpera||"KeyboardEvent"in window?function(e){return 0|(e.ctrlKey?1:0)|(e.altKey?2:0)|(e.shiftKey?4:0)|(e.metaKey?8:0)}:function(e){return 0|(e.metaKey?1:0)|(e.altKey?2:0)|(e.shiftKey?4:0)|(e.ctrlKey?8:0)};t.getModifierString=function(e){return r.KEY_MODS[u(e)]},t.addCommandKeyListener=function(e,n){var r=t.addListener;if(i.isOldGecko||i.isOpera&&!("KeyboardEvent"in window)){var o=null;r(e,"keydown",function(e){o=e.keyCode}),r(e,"keypress",function(e){return a(n,e,o)})}else{var u=null;r(e,"keydown",function(e){s[e.keyCode]=(s[e.keyCode]||0)+1;var t=a(n,e,e.keyCode);return u=e.defaultPrevented,t}),r(e,"keypress",function(e){u&&(e.ctrlKey||e.altKey||e.shiftKey||e.metaKey)&&(t.stopEvent(e),u=null)}),r(e,"keyup",function(e){s[e.keyCode]=null}),s||(f(),r(window,"focus",f))}};if(typeof window=="object"&&window.postMessage&&!i.isOldIE){var l=1;t.nextTick=function(e,n){n=n||window;var r="zero-timeout-message-"+l++,i=function(s){s.data==r&&(t.stopPropagation(s),t.removeListener(n,"message",i),e())};t.addListener(n,"message",i),n.postMessage(r,"*")}}t.$idleBlocked=!1,t.onIdle=function(e,n){return setTimeout(function r(){t.$idleBlocked?setTimeout(r,100):e()},n)},t.$idleBlockId=null,t.blockIdle=function(e){t.$idleBlockId&&clearTimeout(t.$idleBlockId),t.$idleBlocked=!0,t.$idleBlockId=setTimeout(function(){t.$idleBlocked=!1},e||100)},t.nextFrame=typeof window=="object"&&(window.requestAnimationFrame||window.mozRequestAnimationFrame||window.webkitRequestAnimationFrame||window.msRequestAnimationFrame||window.oRequestAnimationFrame),t.nextFrame?t.nextFrame=t.nextFrame.bind(window):t.nextFrame=function(e){setTimeout(e,17)}}),ace.define("ace/range",["require","exports","module"],function(e,t,n){"use strict";var r=function(e,t){return e.row-t.row||e.column-t.column},i=function(e,t,n,r){this.start={row:e,column:t},this.end={row:n,column:r}};(function(){this.isEqual=function(e){return this.start.row===e.start.row&&this.end.row===e.end.row&&this.start.column===e.start.column&&this.end.column===e.end.column},this.toString=function(){return"Range: ["+this.start.row+"/"+this.start.column+"] -> ["+this.end.row+"/"+this.end.column+"]"},this.contains=function(e,t){return this.compare(e,t)==0},this.compareRange=function(e){var t,n=e.end,r=e.start;return t=this.compare(n.row,n.column),t==1?(t=this.compare(r.row,r.column),t==1?2:t==0?1:0):t==-1?-2:(t=this.compare(r.row,r.column),t==-1?-1:t==1?42:0)},this.comparePoint=function(e){return this.compare(e.row,e.column)},this.containsRange=function(e){return this.comparePoint(e.start)==0&&this.comparePoint(e.end)==0},this.intersects=function(e){var t=this.compareRange(e);return t==-1||t==0||t==1},this.isEnd=function(e,t){return this.end.row==e&&this.end.column==t},this.isStart=function(e,t){return this.start.row==e&&this.start.column==t},this.setStart=function(e,t){typeof e=="object"?(this.start.column=e.column,this.start.row=e.row):(this.start.row=e,this.start.column=t)},this.setEnd=function(e,t){typeof e=="object"?(this.end.column=e.column,this.end.row=e.row):(this.end.row=e,this.end.column=t)},this.inside=function(e,t){return this.compare(e,t)==0?this.isEnd(e,t)||this.isStart(e,t)?!1:!0:!1},this.insideStart=function(e,t){return this.compare(e,t)==0?this.isEnd(e,t)?!1:!0:!1},this.insideEnd=function(e,t){return this.compare(e,t)==0?this.isStart(e,t)?!1:!0:!1},this.compare=function(e,t){return!this.isMultiLine()&&e===this.start.row?tthis.end.column?1:0:ethis.end.row?1:this.start.row===e?t>=this.start.column?0:-1:this.end.row===e?t<=this.end.column?0:1:0},this.compareStart=function(e,t){return this.start.row==e&&this.start.column==t?-1:this.compare(e,t)},this.compareEnd=function(e,t){return this.end.row==e&&this.end.column==t?1:this.compare(e,t)},this.compareInside=function(e,t){return this.end.row==e&&this.end.column==t?1:this.start.row==e&&this.start.column==t?-1:this.compare(e,t)},this.clipRows=function(e,t){if(this.end.row>t)var n={row:t+1,column:0};else if(this.end.rowt)var r={row:t+1,column:0};else if(this.start.row0){t&1&&(n+=e);if(t>>=1)e+=e}return n};var r=/^\s\s*/,i=/\s\s*$/;t.stringTrimLeft=function(e){return e.replace(r,"")},t.stringTrimRight=function(e){return e.replace(i,"")},t.copyObject=function(e){var t={};for(var n in e)t[n]=e[n];return t},t.copyArray=function(e){var t=[];for(var n=0,r=e.length;n63,l=400,c=e("../lib/keys"),h=c.KEY_MODS,p=i.isIOS,d=p?/\s/:/\n/,v=function(e,t){function W(){x=!0,n.blur(),n.focus(),x=!1}function V(e){e.keyCode==27&&n.value.lengthC&&T[s]=="\n")o=c.end;else if(rC&&T.slice(0,s).split("\n").length>2)o=c.down;else if(s>C&&T[s-1]==" ")o=c.right,u=h.option;else if(s>C||s==C&&C!=N&&r==s)o=c.right;r!==s&&(u|=h.shift),o&&(t.onCommandKey(null,u,o),N=r,C=s,A(""))};document.addEventListener("selectionchange",s),t.on("destroy",function(){document.removeEventListener("selectionchange",s)})}var n=s.createElement("textarea");n.className="ace_text-input",n.setAttribute("wrap","off"),n.setAttribute("autocorrect","off"),n.setAttribute("autocapitalize","off"),n.setAttribute("spellcheck",!1),n.style.opacity="0",e.insertBefore(n,e.firstChild);var v=!1,m=!1,g=!1,y=!1,b="",w=!0,E=!1;i.isMobile||(n.style.fontSize="1px");var S=!1,x=!1,T="",N=0,C=0;try{var k=document.activeElement===n}catch(L){}r.addListener(n,"blur",function(e){if(x)return;t.onBlur(e),k=!1}),r.addListener(n,"focus",function(e){if(x)return;k=!0;if(i.isEdge)try{if(!document.hasFocus())return}catch(e){}t.onFocus(e),i.isEdge?setTimeout(A):A()}),this.$focusScroll=!1,this.focus=function(){if(b||f||this.$focusScroll=="browser")return n.focus({preventScroll:!0});var e=n.style.top;n.style.position="fixed",n.style.top="0px";try{var t=n.getBoundingClientRect().top!=0}catch(r){return}var i=[];if(t){var s=n.parentElement;while(s&&s.nodeType==1)i.push(s),s.setAttribute("ace_nocontext",!0),!s.parentElement&&s.getRootNode?s=s.getRootNode().host:s=s.parentElement}n.focus({preventScroll:!0}),t&&i.forEach(function(e){e.removeAttribute("ace_nocontext")}),setTimeout(function(){n.style.position="",n.style.top=="0px"&&(n.style.top=e)},0)},this.blur=function(){n.blur()},this.isFocused=function(){return k},t.on("beforeEndOperation",function(){if(t.curOp&&t.curOp.command.name=="insertstring")return;g&&(T=n.value="",z()),A()});var A=p?function(e){if(!k||v&&!e||y)return;e||(e="");var r="\n ab"+e+"cde fg\n";r!=n.value&&(n.value=T=r);var i=4,s=4+(e.length||(t.selection.isEmpty()?0:1));(N!=i||C!=s)&&n.setSelectionRange(i,s),N=i,C=s}:function(){if(g||y)return;if(!k&&!D)return;g=!0;var e=t.selection,r=e.getRange(),i=e.cursor.row,s=r.start.column,o=r.end.column,u=t.session.getLine(i);if(r.start.row!=i){var a=t.session.getLine(i-1);s=r.start.rowi+1?f.length:o,o+=u.length+1,u=u+"\n"+f}u.length>l&&(s=T.length&&e.value===T&&T&&e.selectionEnd!==C},M=function(e){if(g)return;v?v=!1:O(n)&&(t.selectAll(),A())},_=null;this.setInputHandler=function(e){_=e},this.getInputHandler=function(){return _};var D=!1,P=function(e,r){D&&(D=!1);if(m)return A(),e&&t.onPaste(e),m=!1,"";var i=n.selectionStart,s=n.selectionEnd,o=N,u=T.length-C,a=e,f=e.length-i,l=e.length-s,c=0;while(o>0&&T[c]==e[c])c++,o--;a=a.slice(c),c=1;while(u>0&&T.length-c>N-1&&T[T.length-c]==e[e.length-c])c++,u--;return f-=c-1,l-=c-1,a=a.slice(0,a.length-c+1),!r&&f==a.length&&!o&&!u&&!l?"":(y=!0,a&&!o&&!u&&!f&&!l||S?t.onTextInput(a):t.onTextInput(a,{extendLeft:o,extendRight:u,restoreStart:f,restoreEnd:l}),y=!1,T=e,N=i,C=s,a)},H=function(e){if(g)return U();var t=n.value,r=P(t,!0);(t.length>l+100||d.test(r))&&A()},B=function(e,t,n){var r=e.clipboardData||window.clipboardData;if(!r||u)return;var i=a||n?"Text":"text/plain";try{return t?r.setData(i,t)!==!1:r.getData(i)}catch(e){if(!n)return B(e,t,!0)}},j=function(e,i){var s=t.getCopyText();if(!s)return r.preventDefault(e);B(e,s)?(p&&(A(s),v=s,setTimeout(function(){v=!1},10)),i?t.onCut():t.onCopy(),r.preventDefault(e)):(v=!0,n.value=s,n.select(),setTimeout(function(){v=!1,A(),i?t.onCut():t.onCopy()}))},F=function(e){j(e,!0)},I=function(e){j(e,!1)},q=function(e){var s=B(e);typeof s=="string"?(s&&t.onPaste(s,e),i.isIE&&setTimeout(A),r.preventDefault(e)):(n.value="",m=!0)};r.addCommandKeyListener(n,t.onCommandKey.bind(t)),r.addListener(n,"select",M),r.addListener(n,"input",H),r.addListener(n,"cut",F),r.addListener(n,"copy",I),r.addListener(n,"paste",q),(!("oncut"in n)||!("oncopy"in n)||!("onpaste"in n))&&r.addListener(e,"keydown",function(e){if(i.isMac&&!e.metaKey||!e.ctrlKey)return;switch(e.keyCode){case 67:I(e);break;case 86:q(e);break;case 88:F(e)}});var R=function(e){if(g||!t.onCompositionStart||t.$readOnly)return;g={};if(S)return;setTimeout(U,0),t.on("mousedown",W);var r=t.getSelectionRange();r.end.row=r.start.row,r.end.column=r.start.column,g.markerRange=r,g.selectionStart=N,t.onCompositionStart(g),g.useTextareaForIME?(n.value="",T="",N=0,C=0):(n.msGetInputContext&&(g.context=n.msGetInputContext()),n.getInputContext&&(g.context=n.getInputContext()))},U=function(){if(!g||!t.onCompositionUpdate||t.$readOnly)return;if(S)return W();if(g.useTextareaForIME)t.onCompositionUpdate(n.value);else{var e=n.value;P(e),g.markerRange&&(g.context&&(g.markerRange.start.column=g.selectionStart=g.context.compositionStartOffset),g.markerRange.end.column=g.markerRange.start.column+C-g.selectionStart)}},z=function(e){if(!t.onCompositionEnd||t.$readOnly)return;g=!1,t.onCompositionEnd(),t.off("mousedown",W),e&&H()},X=o.delayedCall(U,50).schedule.bind(null,null);r.addListener(n,"compositionstart",R),r.addListener(n,"compositionupdate",U),r.addListener(n,"keyup",V),r.addListener(n,"keydown",X),r.addListener(n,"compositionend",z),this.getElement=function(){return n},this.setCommandMode=function(e){S=e,n.readOnly=!1},this.setReadOnly=function(e){S||(n.readOnly=e)},this.setCopyWithEmptySelection=function(e){E=e},this.onContextMenu=function(e){D=!0,A(),t._emit("nativecontextmenu",{target:t,domEvent:e}),this.moveToMouse(e,!0)},this.moveToMouse=function(e,o){b||(b=n.style.cssText),n.style.cssText=(o?"z-index:100000;":"")+(i.isIE?"opacity:0.1;":"")+"text-indent: -"+(N+C)*t.renderer.characterWidth*.5+"px;";var u=t.container.getBoundingClientRect(),a=s.computedStyle(t.container),f=u.top+(parseInt(a.borderTopWidth)||0),l=u.left+(parseInt(u.borderLeftWidth)||0),c=u.bottom-f-n.clientHeight-2,h=function(e){s.translate(n,e.clientX-l-2,Math.min(e.clientY-f-2,c))};h(e);if(e.type!="mousedown")return;t.renderer.$isMousePressed=!0,clearTimeout($),i.isWin&&r.capture(t.container,h,J)},this.onContextMenuClose=J;var $,K=function(e){t.textInput.onContextMenu(e),J()};r.addListener(n,"mouseup",K),r.addListener(n,"mousedown",function(e){e.preventDefault(),J()}),r.addListener(t.renderer.scroller,"contextmenu",K),r.addListener(n,"contextmenu",K),p&&Q(e,t,n)};t.TextInput=v}),ace.define("ace/mouse/default_handlers",["require","exports","module","ace/lib/useragent"],function(e,t,n){"use strict";function o(e){e.$clickSelection=null;var t=e.editor;t.setDefaultHandler("mousedown",this.onMouseDown.bind(e)),t.setDefaultHandler("dblclick",this.onDoubleClick.bind(e)),t.setDefaultHandler("tripleclick",this.onTripleClick.bind(e)),t.setDefaultHandler("quadclick",this.onQuadClick.bind(e)),t.setDefaultHandler("mousewheel",this.onMouseWheel.bind(e));var n=["select","startSelect","selectEnd","selectAllEnd","selectByWordsEnd","selectByLinesEnd","dragWait","dragWaitEnd","focusWait"];n.forEach(function(t){e[t]=this[t]},this),e.selectByLines=this.extendSelectionBy.bind(e,"getLineRange"),e.selectByWords=this.extendSelectionBy.bind(e,"getWordRange")}function u(e,t,n,r){return Math.sqrt(Math.pow(n-e,2)+Math.pow(r-t,2))}function a(e,t){if(e.start.row==e.end.row)var n=2*t.column-e.start.column-e.end.column;else if(e.start.row==e.end.row-1&&!e.start.column&&!e.end.column)var n=t.column-4;else var n=2*t.row-e.start.row-e.end.row;return n<0?{cursor:e.start,anchor:e.end}:{cursor:e.end,anchor:e.start}}var r=e("../lib/useragent"),i=0,s=550;(function(){this.onMouseDown=function(e){var t=e.inSelection(),n=e.getDocumentPosition();this.mousedownEvent=e;var i=this.editor,s=e.getButton();if(s!==0){var o=i.getSelectionRange(),u=o.isEmpty();(u||s==1)&&i.selection.moveToPosition(n),s==2&&(i.textInput.onContextMenu(e.domEvent),r.isMozilla||e.preventDefault());return}this.mousedownEvent.time=Date.now();if(t&&!i.isFocused()){i.focus();if(this.$focusTimeout&&!this.$clickSelection&&!i.inMultiSelectMode){this.setState("focusWait"),this.captureMouse(e);return}}return this.captureMouse(e),this.startSelect(n,e.domEvent._clicks>1),e.preventDefault()},this.startSelect=function(e,t){e=e||this.editor.renderer.screenToTextCoordinates(this.x,this.y);var n=this.editor;if(!this.mousedownEvent)return;this.mousedownEvent.getShiftKey()?n.selection.selectToPosition(e):t||n.selection.moveToPosition(e),t||this.select(),n.renderer.scroller.setCapture&&n.renderer.scroller.setCapture(),n.setStyle("ace_selecting"),this.setState("select")},this.select=function(){var e,t=this.editor,n=t.renderer.screenToTextCoordinates(this.x,this.y);if(this.$clickSelection){var r=this.$clickSelection.comparePoint(n);if(r==-1)e=this.$clickSelection.end;else if(r==1)e=this.$clickSelection.start;else{var i=a(this.$clickSelection,n);n=i.cursor,e=i.anchor}t.selection.setSelectionAnchor(e.row,e.column)}t.selection.selectToPosition(n),t.renderer.scrollCursorIntoView()},this.extendSelectionBy=function(e){var t,n=this.editor,r=n.renderer.screenToTextCoordinates(this.x,this.y),i=n.selection[e](r.row,r.column);if(this.$clickSelection){var s=this.$clickSelection.comparePoint(i.start),o=this.$clickSelection.comparePoint(i.end);if(s==-1&&o<=0){t=this.$clickSelection.end;if(i.end.row!=r.row||i.end.column!=r.column)r=i.start}else if(o==1&&s>=0){t=this.$clickSelection.start;if(i.start.row!=r.row||i.start.column!=r.column)r=i.end}else if(s==-1&&o==1)r=i.end,t=i.start;else{var u=a(this.$clickSelection,r);r=u.cursor,t=u.anchor}n.selection.setSelectionAnchor(t.row,t.column)}n.selection.selectToPosition(r),n.renderer.scrollCursorIntoView()},this.selectEnd=this.selectAllEnd=this.selectByWordsEnd=this.selectByLinesEnd=function(){this.$clickSelection=null,this.editor.unsetStyle("ace_selecting"),this.editor.renderer.scroller.releaseCapture&&this.editor.renderer.scroller.releaseCapture()},this.focusWait=function(){var e=u(this.mousedownEvent.x,this.mousedownEvent.y,this.x,this.y),t=Date.now();(e>i||t-this.mousedownEvent.time>this.$focusTimeout)&&this.startSelect(this.mousedownEvent.getDocumentPosition())},this.onDoubleClick=function(e){var t=e.getDocumentPosition(),n=this.editor,r=n.session,i=r.getBracketRange(t);i?(i.isEmpty()&&(i.start.column--,i.end.column++),this.setState("select")):(i=n.selection.getWordRange(t.row,t.column),this.setState("selectByWords")),this.$clickSelection=i,this.select()},this.onTripleClick=function(e){var t=e.getDocumentPosition(),n=this.editor;this.setState("selectByLines");var r=n.getSelectionRange();r.isMultiLine()&&r.contains(t.row,t.column)?(this.$clickSelection=n.selection.getLineRange(r.start.row),this.$clickSelection.end=n.selection.getLineRange(r.end.row).end):this.$clickSelection=n.selection.getLineRange(t.row),this.select()},this.onQuadClick=function(e){var t=this.editor;t.selectAll(),this.$clickSelection=t.getSelectionRange(),this.setState("selectAll")},this.onMouseWheel=function(e){if(e.getAccelKey())return;e.getShiftKey()&&e.wheelY&&!e.wheelX&&(e.wheelX=e.wheelY,e.wheelY=0);var t=this.editor;this.$lastScroll||(this.$lastScroll={t:0,vx:0,vy:0,allowed:0});var n=this.$lastScroll,r=e.domEvent.timeStamp,i=r-n.t,o=i?e.wheelX/i:n.vx,u=i?e.wheelY/i:n.vy;i=1&&t.renderer.isScrollableBy(e.wheelX*e.speed,0)&&(f=!0),a<=1&&t.renderer.isScrollableBy(0,e.wheelY*e.speed)&&(f=!0);if(f)n.allowed=r;else if(r-n.allowedt.session.documentToScreenRow(l.row,l.column))return c()}if(f==s)return;f=s.text.join("
"),i.setHtml(f),i.show(),t._signal("showGutterTooltip",i),t.on("mousewheel",c);if(e.$tooltipFollowsMouse)h(u);else{var p=u.domEvent.target,d=p.getBoundingClientRect(),v=i.getElement().style;v.left=d.right+"px",v.top=d.bottom+"px"}}function c(){o&&(o=clearTimeout(o)),f&&(i.hide(),f=null,t._signal("hideGutterTooltip",i),t.removeEventListener("mousewheel",c))}function h(e){i.setPosition(e.x,e.y)}var t=e.editor,n=t.renderer.$gutterLayer,i=new a(t.container);e.editor.setDefaultHandler("guttermousedown",function(r){if(!t.isFocused()||r.getButton()!=0)return;var i=n.getRegion(r);if(i=="foldWidgets")return;var s=r.getDocumentPosition().row,o=t.session.selection;if(r.getShiftKey())o.selectTo(s,0);else{if(r.domEvent.detail==2)return t.selectAll(),r.preventDefault();e.$clickSelection=t.selection.getLineRange(s)}return e.setState("selectByLines"),e.captureMouse(r),r.preventDefault()});var o,u,f;e.editor.setDefaultHandler("guttermousemove",function(t){var n=t.domEvent.target||t.domEvent.srcElement;if(r.hasCssClass(n,"ace_fold-widget"))return c();f&&e.$tooltipFollowsMouse&&h(t),u=t;if(o)return;o=setTimeout(function(){o=null,u&&!e.isMousePressed?l():c()},50)}),s.addListener(t.renderer.$gutter,"mouseout",function(e){u=null;if(!f||o)return;o=setTimeout(function(){o=null,c()},50)}),t.on("changeSession",c)}function a(e){o.call(this,e)}var r=e("../lib/dom"),i=e("../lib/oop"),s=e("../lib/event"),o=e("../tooltip").Tooltip;i.inherits(a,o),function(){this.setPosition=function(e,t){var n=window.innerWidth||document.documentElement.clientWidth,r=window.innerHeight||document.documentElement.clientHeight,i=this.getWidth(),s=this.getHeight();e+=15,t+=15,e+i>n&&(e-=e+i-n),t+s>r&&(t-=20+s),o.prototype.setPosition.call(this,e,t)}}.call(a.prototype),t.GutterHandler=u}),ace.define("ace/mouse/mouse_event",["require","exports","module","ace/lib/event","ace/lib/useragent"],function(e,t,n){"use strict";var r=e("../lib/event"),i=e("../lib/useragent"),s=t.MouseEvent=function(e,t){this.domEvent=e,this.editor=t,this.x=this.clientX=e.clientX,this.y=this.clientY=e.clientY,this.$pos=null,this.$inSelection=null,this.propagationStopped=!1,this.defaultPrevented=!1};(function(){this.stopPropagation=function(){r.stopPropagation(this.domEvent),this.propagationStopped=!0},this.preventDefault=function(){r.preventDefault(this.domEvent),this.defaultPrevented=!0},this.stop=function(){this.stopPropagation(),this.preventDefault()},this.getDocumentPosition=function(){return this.$pos?this.$pos:(this.$pos=this.editor.renderer.screenToTextCoordinates(this.clientX,this.clientY),this.$pos)},this.inSelection=function(){if(this.$inSelection!==null)return this.$inSelection;var e=this.editor,t=e.getSelectionRange();if(t.isEmpty())this.$inSelection=!1;else{var n=this.getDocumentPosition();this.$inSelection=t.contains(n.row,n.column)}return this.$inSelection},this.getButton=function(){return r.getButton(this.domEvent)},this.getShiftKey=function(){return this.domEvent.shiftKey},this.getAccelKey=i.isMac?function(){return this.domEvent.metaKey}:function(){return this.domEvent.ctrlKey}}).call(s.prototype)}),ace.define("ace/mouse/dragdrop_handler",["require","exports","module","ace/lib/dom","ace/lib/event","ace/lib/useragent"],function(e,t,n){"use strict";function f(e){function T(e,n){var r=Date.now(),i=!n||e.row!=n.row,s=!n||e.column!=n.column;if(!S||i||s)t.moveCursorToPosition(e),S=r,x={x:p,y:d};else{var o=l(x.x,x.y,p,d);o>a?S=null:r-S>=u&&(t.renderer.scrollCursorIntoView(),S=null)}}function N(e,n){var r=Date.now(),i=t.renderer.layerConfig.lineHeight,s=t.renderer.layerConfig.characterWidth,u=t.renderer.scroller.getBoundingClientRect(),a={x:{left:p-u.left,right:u.right-p},y:{top:d-u.top,bottom:u.bottom-d}},f=Math.min(a.x.left,a.x.right),l=Math.min(a.y.top,a.y.bottom),c={row:e.row,column:e.column};f/s<=2&&(c.column+=a.x.left=o&&t.renderer.scrollCursorIntoView(c):E=r:E=null}function C(){var e=g;g=t.renderer.screenToTextCoordinates(p,d),T(g,e),N(g,e)}function k(){m=t.selection.toOrientedRange(),h=t.session.addMarker(m,"ace_selection",t.getSelectionStyle()),t.clearSelection(),t.isFocused()&&t.renderer.$cursorLayer.setBlinking(!1),clearInterval(v),C(),v=setInterval(C,20),y=0,i.addListener(document,"mousemove",O)}function L(){clearInterval(v),t.session.removeMarker(h),h=null,t.selection.fromOrientedRange(m),t.isFocused()&&!w&&t.$resetCursorStyle(),m=null,g=null,y=0,E=null,S=null,i.removeListener(document,"mousemove",O)}function O(){A==null&&(A=setTimeout(function(){A!=null&&h&&L()},20))}function M(e){var t=e.types;return!t||Array.prototype.some.call(t,function(e){return e=="text/plain"||e=="Text"})}function _(e){var t=["copy","copymove","all","uninitialized"],n=["move","copymove","linkmove","all","uninitialized"],r=s.isMac?e.altKey:e.ctrlKey,i="uninitialized";try{i=e.dataTransfer.effectAllowed.toLowerCase()}catch(e){}var o="none";return r&&t.indexOf(i)>=0?o="copy":n.indexOf(i)>=0?o="move":t.indexOf(i)>=0&&(o="copy"),o}var t=e.editor,n=r.createElement("img");n.src="data:image/gif;base64,R0lGODlhAQABAAAAACH5BAEKAAEALAAAAAABAAEAAAICTAEAOw==",s.isOpera&&(n.style.cssText="width:1px;height:1px;position:fixed;top:0;left:0;z-index:2147483647;opacity:0;");var f=["dragWait","dragWaitEnd","startDrag","dragReadyEnd","onMouseDrag"];f.forEach(function(t){e[t]=this[t]},this),t.addEventListener("mousedown",this.onMouseDown.bind(e));var c=t.container,h,p,d,v,m,g,y=0,b,w,E,S,x;this.onDragStart=function(e){if(this.cancelDrag||!c.draggable){var r=this;return setTimeout(function(){r.startSelect(),r.captureMouse(e)},0),e.preventDefault()}m=t.getSelectionRange();var i=e.dataTransfer;i.effectAllowed=t.getReadOnly()?"copy":"copyMove",s.isOpera&&(t.container.appendChild(n),n.scrollTop=0),i.setDragImage&&i.setDragImage(n,0,0),s.isOpera&&t.container.removeChild(n),i.clearData(),i.setData("Text",t.session.getTextRange()),w=!0,this.setState("drag")},this.onDragEnd=function(e){c.draggable=!1,w=!1,this.setState(null);if(!t.getReadOnly()){var n=e.dataTransfer.dropEffect;!b&&n=="move"&&t.session.remove(t.getSelectionRange()),t.$resetCursorStyle()}this.editor.unsetStyle("ace_dragging"),this.editor.renderer.setCursorStyle("")},this.onDragEnter=function(e){if(t.getReadOnly()||!M(e.dataTransfer))return;return p=e.clientX,d=e.clientY,h||k(),y++,e.dataTransfer.dropEffect=b=_(e),i.preventDefault(e)},this.onDragOver=function(e){if(t.getReadOnly()||!M(e.dataTransfer))return;return p=e.clientX,d=e.clientY,h||(k(),y++),A!==null&&(A=null),e.dataTransfer.dropEffect=b=_(e),i.preventDefault(e)},this.onDragLeave=function(e){y--;if(y<=0&&h)return L(),b=null,i.preventDefault(e)},this.onDrop=function(e){if(!g)return;var n=e.dataTransfer;if(w)switch(b){case"move":m.contains(g.row,g.column)?m={start:g,end:g}:m=t.moveText(m,g);break;case"copy":m=t.moveText(m,g,!0)}else{var r=n.getData("Text");m={start:g,end:t.session.insert(g,r)},t.focus(),b=null}return L(),i.preventDefault(e)},i.addListener(c,"dragstart",this.onDragStart.bind(e)),i.addListener(c,"dragend",this.onDragEnd.bind(e)),i.addListener(c,"dragenter",this.onDragEnter.bind(e)),i.addListener(c,"dragover",this.onDragOver.bind(e)),i.addListener(c,"dragleave",this.onDragLeave.bind(e)),i.addListener(c,"drop",this.onDrop.bind(e));var A=null}function l(e,t,n,r){return Math.sqrt(Math.pow(n-e,2)+Math.pow(r-t,2))}var r=e("../lib/dom"),i=e("../lib/event"),s=e("../lib/useragent"),o=200,u=200,a=5;(function(){this.dragWait=function(){var e=Date.now()-this.mousedownEvent.time;e>this.editor.getDragDelay()&&this.startDrag()},this.dragWaitEnd=function(){var e=this.editor.container;e.draggable=!1,this.startSelect(this.mousedownEvent.getDocumentPosition()),this.selectEnd()},this.dragReadyEnd=function(e){this.editor.$resetCursorStyle(),this.editor.unsetStyle("ace_dragging"),this.editor.renderer.setCursorStyle(""),this.dragWaitEnd()},this.startDrag=function(){this.cancelDrag=!1;var e=this.editor,t=e.container;t.draggable=!0,e.renderer.$cursorLayer.setBlinking(!1),e.setStyle("ace_dragging");var n=s.isWin?"default":"move";e.renderer.setCursorStyle(n),this.setState("dragReady")},this.onMouseDrag=function(e){var t=this.editor.container;if(s.isIE&&this.state=="dragReady"){var n=l(this.mousedownEvent.x,this.mousedownEvent.y,this.x,this.y);n>3&&t.dragDrop()}if(this.state==="dragWait"){var n=l(this.mousedownEvent.x,this.mousedownEvent.y,this.x,this.y);n>0&&(t.draggable=!1,this.startSelect(this.mousedownEvent.getDocumentPosition()))}},this.onMouseDown=function(e){if(!this.$dragEnabled)return;this.mousedownEvent=e;var t=this.editor,n=e.inSelection(),r=e.getButton(),i=e.domEvent.detail||1;if(i===1&&r===0&&n){if(e.editor.inMultiSelectMode&&(e.getAccelKey()||e.getShiftKey()))return;this.mousedownEvent.time=Date.now();var o=e.domEvent.target||e.domEvent.srcElement;"unselectable"in o&&(o.unselectable="on");if(t.getDragDelay()){if(s.isWebKit){this.cancelDrag=!0;var u=t.container;u.draggable=!0}this.setState("dragWait")}else this.startDrag();this.captureMouse(e,this.onMouseDrag.bind(this)),e.defaultPrevented=!0}}}).call(f.prototype),t.DragdropHandler=f}),ace.define("ace/mouse/touch_handler",["require","exports","module","ace/mouse/mouse_event"],function(e,t,n){"use strict";var r=e("./mouse_event").MouseEvent;t.addTouchListeners=function(e,t){function m(){a=null,clearTimeout(a),t.selection.isEmpty()&&t.selection.moveToPosition(c),n="wait"}function g(){a=null,clearTimeout(a),t.selection.moveToPosition(c);var e=h>=2?t.selection.getLineRange(c.row):t.session.getBracketRange(c);e&&!e.isEmpty()?t.selection.setRange(e):t.selection.selectWord(),n="wait"}function y(){l+=60,f=setInterval(function(){l--<=0&&(clearInterval(f),f=null),Math.abs(p)<.01&&(p=0),Math.abs(d)<.01&&(d=0),l<20&&(p=.9*p),l<20&&(d=.9*d),t.renderer.scrollBy(10*p,10*d)},10)}var n="scroll",i,s,o,u,a,f,l=0,c,h=0,p=0,d=0,v;e.addEventListener("contextmenu",function(e){if(!v)return;var n=t.textInput.getElement();n.focus()}),e.addEventListener("touchstart",function(e){var f=e.touches;if(a||f.length>1){clearTimeout(a),a=null,n="zoom";return}v=t.$mouseHandler.isMousePressed=!0;var y=f[0];i=y.clientX,s=y.clientY,p=d=0,e.clientX=y.clientX,e.clientY=y.clientY;var b=e.timeStamp;u=b;var w=new r(e,t);c=w.getDocumentPosition();if(b-o<500&&f.length==1&&!l)h++,e.preventDefault(),e.button=0,g();else{h=0,a=setTimeout(m,450);var E=t.selection.cursor,S=t.selection.isEmpty()?E:t.selection.anchor,x=t.renderer.$cursorLayer.getPixelPosition(E,!0),T=t.renderer.$cursorLayer.getPixelPosition(S,!0),N=t.renderer.scroller.getBoundingClientRect(),C=t.renderer.layerConfig.lineHeight,k=t.renderer.layerConfig.lineHeight,L=function(e,t){return e/=k,t=t/C-.75,e*e+t*t},A=L(e.clientX-N.left-x.left,e.clientY-N.top-x.top),O=L(e.clientX-N.left-T.left,e.clientY-N.top-T.top);A<3.5&&O<3.5&&(n=A>O?"cursor":"anchor"),O<3.5?n="anchor":A<3.5?n="cursor":n="scroll"}o=b}),e.addEventListener("touchend",function(e){v=t.$mouseHandler.isMousePressed=!1,f&&clearInterval(f),n=="zoom"?(n="",l=0):a?(t.selection.moveToPosition(c),l=0):n=="scroll"&&(y(),e.preventDefault()),clearTimeout(a),a=null}),e.addEventListener("touchmove",function(e){a&&(clearTimeout(a),a=null);var o=e.touches;if(o.length>1||n=="zoom")return;var f=o[0],l=i-f.clientX,c=s-f.clientY;if(n=="wait"){if(!(l*l+c*c>4))return e.preventDefault();n="cursor"}i=f.clientX,s=f.clientY,e.clientX=f.clientX,e.clientY=f.clientY;var h=e.timeStamp,v=h-u;u=h;if(n=="scroll"){var m=new r(e,t);m.speed=1,m.wheelX=l,m.wheelY=c,10*Math.abs(l)1&&(i=n[n.length-2]);var o=a[t+"Path"];return o==null?o=a.basePath:r=="/"&&(t=r=""),o&&o.slice(-1)!="/"&&(o+="/"),o+t+r+i+this.get("suffix")},t.setModuleUrl=function(e,t){return a.$moduleUrls[e]=t},t.$loading={},t.loadModule=function(n,r){var i,o;Array.isArray(n)&&(o=n[0],n=n[1]);try{i=e(n)}catch(u){}if(i&&!t.$loading[n])return r&&r(i);t.$loading[n]||(t.$loading[n]=[]),t.$loading[n].push(r);if(t.$loading[n].length>1)return;var a=function(){e([n],function(e){t._emit("load.module",{name:n,module:e});var r=t.$loading[n];t.$loading[n]=null,r.forEach(function(t){t&&t(e)})})};if(!t.get("packaged"))return a();s.loadScript(t.moduleUrl(n,o),a),f()};var f=function(){!a.basePath&&!a.workerPath&&!a.modePath&&!a.themePath&&!Object.keys(a.$moduleUrls).length&&(console.error("Unable to infer path to ace from script src,","use ace.config.set('basePath', 'path') to enable dynamic loading of modes and themes","or with webpack use ace/webpack-resolver"),f=function(){})};t.init=l,t.version="1.4.5"}),ace.define("ace/mouse/mouse_handler",["require","exports","module","ace/lib/event","ace/lib/useragent","ace/mouse/default_handlers","ace/mouse/default_gutter_handler","ace/mouse/mouse_event","ace/mouse/dragdrop_handler","ace/mouse/touch_handler","ace/config"],function(e,t,n){"use strict";var r=e("../lib/event"),i=e("../lib/useragent"),s=e("./default_handlers").DefaultHandlers,o=e("./default_gutter_handler").GutterHandler,u=e("./mouse_event").MouseEvent,a=e("./dragdrop_handler").DragdropHandler,f=e("./touch_handler").addTouchListeners,l=e("../config"),c=function(e){var t=this;this.editor=e,new s(this),new o(this),new a(this);var n=function(t){var n=!document.hasFocus||!document.hasFocus()||!e.isFocused()&&document.activeElement==(e.textInput&&e.textInput.getElement());n&&window.focus(),e.focus()},u=e.renderer.getMouseEventTarget();r.addListener(u,"click",this.onMouseEvent.bind(this,"click")),r.addListener(u,"mousemove",this.onMouseMove.bind(this,"mousemove")),r.addMultiMouseDownListener([u,e.renderer.scrollBarV&&e.renderer.scrollBarV.inner,e.renderer.scrollBarH&&e.renderer.scrollBarH.inner,e.textInput&&e.textInput.getElement()].filter(Boolean),[400,300,250],this,"onMouseEvent"),r.addMouseWheelListener(e.container,this.onMouseWheel.bind(this,"mousewheel")),f(e.container,e);var l=e.renderer.$gutter;r.addListener(l,"mousedown",this.onMouseEvent.bind(this,"guttermousedown")),r.addListener(l,"click",this.onMouseEvent.bind(this,"gutterclick")),r.addListener(l,"dblclick",this.onMouseEvent.bind(this,"gutterdblclick")),r.addListener(l,"mousemove",this.onMouseEvent.bind(this,"guttermousemove")),r.addListener(u,"mousedown",n),r.addListener(l,"mousedown",n),i.isIE&&e.renderer.scrollBarV&&(r.addListener(e.renderer.scrollBarV.element,"mousedown",n),r.addListener(e.renderer.scrollBarH.element,"mousedown",n)),e.on("mousemove",function(n){if(t.state||t.$dragDelay||!t.$dragEnabled)return;var r=e.renderer.screenToTextCoordinates(n.x,n.y),i=e.session.selection.getRange(),s=e.renderer;!i.isEmpty()&&i.insideStart(r.row,r.column)?s.setCursorStyle("default"):s.setCursorStyle("")})};(function(){this.onMouseEvent=function(e,t){this.editor._emit(e,new u(t,this.editor))},this.onMouseMove=function(e,t){var n=this.editor._eventRegistry&&this.editor._eventRegistry.mousemove;if(!n||!n.length)return;this.editor._emit(e,new u(t,this.editor))},this.onMouseWheel=function(e,t){var n=new u(t,this.editor);n.speed=this.$scrollSpeed*2,n.wheelX=t.wheelX,n.wheelY=t.wheelY,this.editor._emit(e,n)},this.setState=function(e){this.state=e},this.captureMouse=function(e,t){this.x=e.x,this.y=e.y,this.isMousePressed=!0;var n=this.editor,s=this.editor.renderer;s.$isMousePressed=!0;var o=this,a=function(e){if(!e)return;if(i.isWebKit&&!e.which&&o.releaseMouse)return o.releaseMouse();o.x=e.clientX,o.y=e.clientY,t&&t(e),o.mouseEvent=new u(e,o.editor),o.$mouseMoved=!0},f=function(e){n.off("beforeEndOperation",c),clearInterval(h),l(),o[o.state+"End"]&&o[o.state+"End"](e),o.state="",o.isMousePressed=s.$isMousePressed=!1,s.$keepTextAreaAtCursor&&s.$moveTextAreaToCursor(),o.$onCaptureMouseMove=o.releaseMouse=null,e&&o.onMouseEvent("mouseup",e),n.endOperation()},l=function(){o[o.state]&&o[o.state](),o.$mouseMoved=!1};if(i.isOldIE&&e.domEvent.type=="dblclick")return setTimeout(function(){f(e)});var c=function(e){if(!o.releaseMouse)return;n.curOp.command.name&&n.curOp.selectionChanged&&(o[o.state+"End"]&&o[o.state+"End"](),o.state="",o.releaseMouse())};n.on("beforeEndOperation",c),n.startOperation({command:{name:"mouse"}}),o.$onCaptureMouseMove=a,o.releaseMouse=r.capture(this.editor.container,a,f);var h=setInterval(l,20)},this.releaseMouse=null,this.cancelContextMenu=function(){var e=function(t){if(t&&t.domEvent&&t.domEvent.type!="contextmenu")return;this.editor.off("nativecontextmenu",e),t&&t.domEvent&&r.stopEvent(t.domEvent)}.bind(this);setTimeout(e,10),this.editor.on("nativecontextmenu",e)}}).call(c.prototype),l.defineOptions(c.prototype,"mouseHandler",{scrollSpeed:{initialValue:2},dragDelay:{initialValue:i.isMac?150:0},dragEnabled:{initialValue:!0},focusTimeout:{initialValue:0},tooltipFollowsMouse:{initialValue:!0}}),t.MouseHandler=c}),ace.define("ace/mouse/fold_handler",["require","exports","module","ace/lib/dom"],function(e,t,n){"use strict";function i(e){e.on("click",function(t){var n=t.getDocumentPosition(),i=e.session,s=i.getFoldAt(n.row,n.column,1);s&&(t.getAccelKey()?i.removeFold(s):i.expandFold(s),t.stop());var o=t.domEvent&&t.domEvent.target;o&&r.hasCssClass(o,"ace_inline_button")&&r.hasCssClass(o,"ace_toggle_wrap")&&(i.setOption("wrap",!i.getUseWrapMode()),e.renderer.scrollCursorIntoView())}),e.on("gutterclick",function(t){var n=e.renderer.$gutterLayer.getRegion(t);if(n=="foldWidgets"){var r=t.getDocumentPosition().row,i=e.session;i.foldWidgets&&i.foldWidgets[r]&&e.session.onFoldWidgetClick(r,t),e.isFocused()||e.focus(),t.stop()}}),e.on("gutterdblclick",function(t){var n=e.renderer.$gutterLayer.getRegion(t);if(n=="foldWidgets"){var r=t.getDocumentPosition().row,i=e.session,s=i.getParentFoldRangeData(r,!0),o=s.range||s.firstRange;if(o){r=o.start.row;var u=i.getFoldAt(r,i.getLine(r).length,1);u?i.removeFold(u):(i.addFold("...",o),e.renderer.scrollCursorIntoView({row:o.start.row,column:0}))}t.stop()}})}var r=e("../lib/dom");t.FoldHandler=i}),ace.define("ace/keyboard/keybinding",["require","exports","module","ace/lib/keys","ace/lib/event"],function(e,t,n){"use strict";var r=e("../lib/keys"),i=e("../lib/event"),s=function(e){this.$editor=e,this.$data={editor:e},this.$handlers=[],this.setDefaultHandler(e.commands)};(function(){this.setDefaultHandler=function(e){this.removeKeyboardHandler(this.$defaultHandler),this.$defaultHandler=e,this.addKeyboardHandler(e,0)},this.setKeyboardHandler=function(e){var t=this.$handlers;if(t[t.length-1]==e)return;while(t[t.length-1]&&t[t.length-1]!=this.$defaultHandler)this.removeKeyboardHandler(t[t.length-1]);this.addKeyboardHandler(e,1)},this.addKeyboardHandler=function(e,t){if(!e)return;typeof e=="function"&&!e.handleKeyboard&&(e.handleKeyboard=e);var n=this.$handlers.indexOf(e);n!=-1&&this.$handlers.splice(n,1),t==undefined?this.$handlers.push(e):this.$handlers.splice(t,0,e),n==-1&&e.attach&&e.attach(this.$editor)},this.removeKeyboardHandler=function(e){var t=this.$handlers.indexOf(e);return t==-1?!1:(this.$handlers.splice(t,1),e.detach&&e.detach(this.$editor),!0)},this.getKeyboardHandler=function(){return this.$handlers[this.$handlers.length-1]},this.getStatusText=function(){var e=this.$data,t=e.editor;return this.$handlers.map(function(n){return n.getStatusText&&n.getStatusText(t,e)||""}).filter(Boolean).join(" ")},this.$callKeyboardHandlers=function(e,t,n,r){var s,o=!1,u=this.$editor.commands;for(var a=this.$handlers.length;a--;){s=this.$handlers[a].handleKeyboard(this.$data,e,t,n,r);if(!s||!s.command)continue;s.command=="null"?o=!0:o=u.exec(s.command,this.$editor,s.args,r),o&&r&&e!=-1&&s.passEvent!=1&&s.command.passEvent!=1&&i.stopEvent(r);if(o)break}return!o&&e==-1&&(s={command:"insertstring"},o=u.exec("insertstring",this.$editor,t)),o&&this.$editor._signal&&this.$editor._signal("keyboardActivity",s),o},this.onCommandKey=function(e,t,n){var i=r.keyCodeToString(n);this.$callKeyboardHandlers(t,i,n,e)},this.onTextInput=function(e){this.$callKeyboardHandlers(-1,e)}}).call(s.prototype),t.KeyBinding=s}),ace.define("ace/lib/bidiutil",["require","exports","module"],function(e,t,n){"use strict";function F(e,t,n,r){var i=s?d:p,c=null,h=null,v=null,m=0,g=null,y=null,b=-1,w=null,E=null,T=[];if(!r)for(w=0,r=[];w0)if(g==16){for(w=b;w-1){for(w=b;w=0;C--){if(r[C]!=N)break;t[C]=s}}}function I(e,t,n){if(o=e){u=i+1;while(u=e)u++;for(a=i,l=u-1;a=t.length||(o=n[r-1])!=b&&o!=w||(c=t[r+1])!=b&&c!=w)return E;return u&&(c=w),c==o?c:E;case k:o=r>0?n[r-1]:S;if(o==b&&r+10&&n[r-1]==b)return b;if(u)return E;p=r+1,h=t.length;while(p=1425&&d<=2303||d==64286;o=t[p];if(v&&(o==y||o==T))return y}if(r<1||(o=t[r-1])==S)return E;return n[r-1];case S:return u=!1,f=!0,s;case x:return l=!0,E;case O:case M:case D:case P:case _:u=!1;case H:return E}}function R(e){var t=e.charCodeAt(0),n=t>>8;return n==0?t>191?g:B[t]:n==5?/[\u0591-\u05f4]/.test(e)?y:g:n==6?/[\u0610-\u061a\u064b-\u065f\u06d6-\u06e4\u06e7-\u06ed]/.test(e)?A:/[\u0660-\u0669\u066b-\u066c]/.test(e)?w:t==1642?L:/[\u06f0-\u06f9]/.test(e)?b:T:n==32&&t<=8287?j[t&255]:n==254?t>=65136?T:E:E}function U(e){return e>="\u064b"&&e<="\u0655"}var r=["\u0621","\u0641"],i=["\u063a","\u064a"],s=0,o=0,u=!1,a=!1,f=!1,l=!1,c=!1,h=!1,p=[[0,3,0,1,0,0,0],[0,3,0,1,2,2,0],[0,3,0,17,2,0,1],[0,3,5,5,4,1,0],[0,3,21,21,4,0,1],[0,3,5,5,4,2,0]],d=[[2,0,1,1,0,1,0],[2,0,1,1,0,2,0],[2,0,2,1,3,2,0],[2,0,2,33,3,1,1]],v=0,m=1,g=0,y=1,b=2,w=3,E=4,S=5,x=6,T=7,N=8,C=9,k=10,L=11,A=12,O=13,M=14,_=15,D=16,P=17,H=18,B=[H,H,H,H,H,H,H,H,H,x,S,x,N,S,H,H,H,H,H,H,H,H,H,H,H,H,H,H,S,S,S,x,N,E,E,L,L,L,E,E,E,E,E,k,C,k,C,C,b,b,b,b,b,b,b,b,b,b,C,E,E,E,E,E,E,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,E,E,E,E,E,E,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,g,E,E,E,E,H,H,H,H,H,H,S,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,H,C,E,L,L,L,L,E,E,E,E,g,E,E,H,E,E,L,L,b,b,E,g,E,E,E,b,g,E,E,E,E,E],j=[N,N,N,N,N,N,N,N,N,N,N,H,H,H,g,y,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,N,S,O,M,_,D,P,C,L,L,L,L,L,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,C,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,E,N];t.L=g,t.R=y,t.EN=b,t.ON_R=3,t.AN=4,t.R_H=5,t.B=6,t.RLE=7,t.DOT="\u00b7",t.doBidiReorder=function(e,n,r){if(e.length<2)return{};var i=e.split(""),o=new Array(i.length),u=new Array(i.length),a=[];s=r?m:v,F(i,a,i.length,n);for(var f=0;fT&&n[f]0&&i[f-1]==="\u0644"&&/\u0622|\u0623|\u0625|\u0627/.test(i[f])&&(a[f-1]=a[f]=t.R_H,f++);i[i.length-1]===t.DOT&&(a[i.length-1]=t.B),i[0]==="\u202b"&&(a[0]=t.RLE);for(var f=0;f=0&&(e=this.session.$docRowCache[n])}return e},this.getSplitIndex=function(){var e=0,t=this.session.$screenRowCache;if(t.length){var n,r=this.session.$getRowCacheIndex(t,this.currentRow);while(this.currentRow-e>0){n=this.session.$getRowCacheIndex(t,this.currentRow-e-1);if(n!==r)break;r=n,e++}}else e=this.currentRow;return e},this.updateRowLine=function(e,t){e===undefined&&(e=this.getDocumentRow());var n=e===this.session.getLength()-1,s=n?this.EOF:this.EOL;this.wrapIndent=0,this.line=this.session.getLine(e),this.isRtlDir=this.$isRtl||this.line.charAt(0)===this.RLE;if(this.session.$useWrapMode){var o=this.session.$wrapData[e];o&&(t===undefined&&(t=this.getSplitIndex()),t>0&&o.length?(this.wrapIndent=o.indent,this.wrapOffset=this.wrapIndent*this.charWidths[r.L],this.line=tt?this.session.getOverwrite()?e:e-1:t,i=r.getVisualFromLogicalIdx(n,this.bidiMap),s=this.bidiMap.bidiLevels,o=0;!this.session.getOverwrite()&&e<=t&&s[i]%2!==0&&i++;for(var u=0;ut&&s[i]%2===0&&(o+=this.charWidths[s[i]]),this.wrapIndent&&(o+=this.isRtlDir?-1*this.wrapOffset:this.wrapOffset),this.isRtlDir&&(o+=this.rtlLineOffset),o},this.getSelections=function(e,t){var n=this.bidiMap,r=n.bidiLevels,i,s=[],o=0,u=Math.min(e,t)-this.wrapIndent,a=Math.max(e,t)-this.wrapIndent,f=!1,l=!1,c=0;this.wrapIndent&&(o+=this.isRtlDir?-1*this.wrapOffset:this.wrapOffset);for(var h,p=0;p=u&&hn+s/2){n+=s;if(r===i.length-1){s=0;break}s=this.charWidths[i[++r]]}return r>0&&i[r-1]%2!==0&&i[r]%2===0?(e0&&i[r-1]%2===0&&i[r]%2!==0?t=1+(e>n?this.bidiMap.logicalFromVisual[r]:this.bidiMap.logicalFromVisual[r-1]):this.isRtlDir&&r===i.length-1&&s===0&&i[r-1]%2===0||!this.isRtlDir&&r===0&&i[r]%2!==0?t=1+this.bidiMap.logicalFromVisual[r]:(r>0&&i[r-1]%2!==0&&s!==0&&r--,t=this.bidiMap.logicalFromVisual[r]),t===0&&this.isRtlDir&&t++,t+this.wrapIndent}}).call(o.prototype),t.BidiHandler=o}),ace.define("ace/selection",["require","exports","module","ace/lib/oop","ace/lib/lang","ace/lib/event_emitter","ace/range"],function(e,t,n){"use strict";var r=e("./lib/oop"),i=e("./lib/lang"),s=e("./lib/event_emitter").EventEmitter,o=e("./range").Range,u=function(e){this.session=e,this.doc=e.getDocument(),this.clearSelection(),this.cursor=this.lead=this.doc.createAnchor(0,0),this.anchor=this.doc.createAnchor(0,0),this.$silent=!1;var t=this;this.cursor.on("change",function(e){t.$cursorChanged=!0,t.$silent||t._emit("changeCursor"),!t.$isEmpty&&!t.$silent&&t._emit("changeSelection"),!t.$keepDesiredColumnOnChange&&e.old.column!=e.value.column&&(t.$desiredColumn=null)}),this.anchor.on("change",function(){t.$anchorChanged=!0,!t.$isEmpty&&!t.$silent&&t._emit("changeSelection")})};(function(){r.implement(this,s),this.isEmpty=function(){return this.$isEmpty||this.anchor.row==this.lead.row&&this.anchor.column==this.lead.column},this.isMultiLine=function(){return!this.$isEmpty&&this.anchor.row!=this.cursor.row},this.getCursor=function(){return this.lead.getPosition()},this.setSelectionAnchor=function(e,t){this.$isEmpty=!1,this.anchor.setPosition(e,t)},this.getAnchor=this.getSelectionAnchor=function(){return this.$isEmpty?this.getSelectionLead():this.anchor.getPosition()},this.getSelectionLead=function(){return this.lead.getPosition()},this.isBackwards=function(){var e=this.anchor,t=this.lead;return e.row>t.row||e.row==t.row&&e.column>t.column},this.getRange=function(){var e=this.anchor,t=this.lead;return this.$isEmpty?o.fromPoints(t,t):this.isBackwards()?o.fromPoints(t,e):o.fromPoints(e,t)},this.clearSelection=function(){this.$isEmpty||(this.$isEmpty=!0,this._emit("changeSelection"))},this.selectAll=function(){this.$setSelection(0,0,Number.MAX_VALUE,Number.MAX_VALUE)},this.setRange=this.setSelectionRange=function(e,t){var n=t?e.end:e.start,r=t?e.start:e.end;this.$setSelection(n.row,n.column,r.row,r.column)},this.$setSelection=function(e,t,n,r){var i=this.$isEmpty,s=this.inMultiSelectMode;this.$silent=!0,this.$cursorChanged=this.$anchorChanged=!1,this.anchor.setPosition(e,t),this.cursor.setPosition(n,r),this.$isEmpty=!o.comparePoints(this.anchor,this.cursor),this.$silent=!1,this.$cursorChanged&&this._emit("changeCursor"),(this.$cursorChanged||this.$anchorChanged||i!=this.$isEmpty||s)&&this._emit("changeSelection")},this.$moveSelection=function(e){var t=this.lead;this.$isEmpty&&this.setSelectionAnchor(t.row,t.column),e.call(this)},this.selectTo=function(e,t){this.$moveSelection(function(){this.moveCursorTo(e,t)})},this.selectToPosition=function(e){this.$moveSelection(function(){this.moveCursorToPosition(e)})},this.moveTo=function(e,t){this.clearSelection(),this.moveCursorTo(e,t)},this.moveToPosition=function(e){this.clearSelection(),this.moveCursorToPosition(e)},this.selectUp=function(){this.$moveSelection(this.moveCursorUp)},this.selectDown=function(){this.$moveSelection(this.moveCursorDown)},this.selectRight=function(){this.$moveSelection(this.moveCursorRight)},this.selectLeft=function(){this.$moveSelection(this.moveCursorLeft)},this.selectLineStart=function(){this.$moveSelection(this.moveCursorLineStart)},this.selectLineEnd=function(){this.$moveSelection(this.moveCursorLineEnd)},this.selectFileEnd=function(){this.$moveSelection(this.moveCursorFileEnd)},this.selectFileStart=function(){this.$moveSelection(this.moveCursorFileStart)},this.selectWordRight=function(){this.$moveSelection(this.moveCursorWordRight)},this.selectWordLeft=function(){this.$moveSelection(this.moveCursorWordLeft)},this.getWordRange=function(e,t){if(typeof t=="undefined"){var n=e||this.lead;e=n.row,t=n.column}return this.session.getWordRange(e,t)},this.selectWord=function(){this.setSelectionRange(this.getWordRange())},this.selectAWord=function(){var e=this.getCursor(),t=this.session.getAWordRange(e.row,e.column);this.setSelectionRange(t)},this.getLineRange=function(e,t){var n=typeof e=="number"?e:this.lead.row,r,i=this.session.getFoldLine(n);return i?(n=i.start.row,r=i.end.row):r=n,t===!0?new o(n,0,r,this.session.getLine(r).length):new o(n,0,r+1,0)},this.selectLine=function(){this.setSelectionRange(this.getLineRange())},this.moveCursorUp=function(){this.moveCursorBy(-1,0)},this.moveCursorDown=function(){this.moveCursorBy(1,0)},this.wouldMoveIntoSoftTab=function(e,t,n){var r=e.column,i=e.column+t;return n<0&&(r=e.column-t,i=e.column),this.session.isTabStop(e)&&this.doc.getLine(e.row).slice(r,i).split(" ").length-1==t},this.moveCursorLeft=function(){var e=this.lead.getPosition(),t;if(t=this.session.getFoldAt(e.row,e.column,-1))this.moveCursorTo(t.start.row,t.start.column);else if(e.column===0)e.row>0&&this.moveCursorTo(e.row-1,this.doc.getLine(e.row-1).length);else{var n=this.session.getTabSize();this.wouldMoveIntoSoftTab(e,n,-1)&&!this.session.getNavigateWithinSoftTabs()?this.moveCursorBy(0,-n):this.moveCursorBy(0,-1)}},this.moveCursorRight=function(){var e=this.lead.getPosition(),t;if(t=this.session.getFoldAt(e.row,e.column,1))this.moveCursorTo(t.end.row,t.end.column);else if(this.lead.column==this.doc.getLine(this.lead.row).length)this.lead.row0&&(t.column=r)}}this.moveCursorTo(t.row,t.column)},this.moveCursorFileEnd=function(){var e=this.doc.getLength()-1,t=this.doc.getLine(e).length;this.moveCursorTo(e,t)},this.moveCursorFileStart=function(){this.moveCursorTo(0,0)},this.moveCursorLongWordRight=function(){var e=this.lead.row,t=this.lead.column,n=this.doc.getLine(e),r=n.substring(t);this.session.nonTokenRe.lastIndex=0,this.session.tokenRe.lastIndex=0;var i=this.session.getFoldAt(e,t,1);if(i){this.moveCursorTo(i.end.row,i.end.column);return}this.session.nonTokenRe.exec(r)&&(t+=this.session.nonTokenRe.lastIndex,this.session.nonTokenRe.lastIndex=0,r=n.substring(t));if(t>=n.length){this.moveCursorTo(e,n.length),this.moveCursorRight(),e0&&this.moveCursorWordLeft();return}this.session.tokenRe.exec(s)&&(t-=this.session.tokenRe.lastIndex,this.session.tokenRe.lastIndex=0),this.moveCursorTo(e,t)},this.$shortWordEndIndex=function(e){var t=0,n,r=/\s/,i=this.session.tokenRe;i.lastIndex=0;if(this.session.tokenRe.exec(e))t=this.session.tokenRe.lastIndex;else{while((n=e[t])&&r.test(n))t++;if(t<1){i.lastIndex=0;while((n=e[t])&&!i.test(n)){i.lastIndex=0,t++;if(r.test(n)){if(t>2){t--;break}while((n=e[t])&&r.test(n))t++;if(t>2)break}}}}return i.lastIndex=0,t},this.moveCursorShortWordRight=function(){var e=this.lead.row,t=this.lead.column,n=this.doc.getLine(e),r=n.substring(t),i=this.session.getFoldAt(e,t,1);if(i)return this.moveCursorTo(i.end.row,i.end.column);if(t==n.length){var s=this.doc.getLength();do e++,r=this.doc.getLine(e);while(e0&&/^\s*$/.test(r));t=r.length,/\s+$/.test(r)||(r="")}var s=i.stringReverse(r),o=this.$shortWordEndIndex(s);return this.moveCursorTo(e,t-o)},this.moveCursorWordRight=function(){this.session.$selectLongWords?this.moveCursorLongWordRight():this.moveCursorShortWordRight()},this.moveCursorWordLeft=function(){this.session.$selectLongWords?this.moveCursorLongWordLeft():this.moveCursorShortWordLeft()},this.moveCursorBy=function(e,t){var n=this.session.documentToScreenPosition(this.lead.row,this.lead.column),r;t===0&&(e!==0&&(this.session.$bidiHandler.isBidiRow(n.row,this.lead.row)?(r=this.session.$bidiHandler.getPosLeft(n.column),n.column=Math.round(r/this.session.$bidiHandler.charWidths[0])):r=n.column*this.session.$bidiHandler.charWidths[0]),this.$desiredColumn?n.column=this.$desiredColumn:this.$desiredColumn=n.column);var i=this.session.screenToDocumentPosition(n.row+e,n.column,r);e!==0&&t===0&&i.row===this.lead.row&&i.column===this.lead.column&&this.session.lineWidgets&&this.session.lineWidgets[i.row]&&(i.row>0||e>0)&&i.row++,this.moveCursorTo(i.row,i.column+t,t===0)},this.moveCursorToPosition=function(e){this.moveCursorTo(e.row,e.column)},this.moveCursorTo=function(e,t,n){var r=this.session.getFoldAt(e,t,1);r&&(e=r.start.row,t=r.start.column),this.$keepDesiredColumnOnChange=!0;var i=this.session.getLine(e);/[\uDC00-\uDFFF]/.test(i.charAt(t))&&i.charAt(t-1)&&(this.lead.row==e&&this.lead.column==t+1?t-=1:t+=1),this.lead.setPosition(e,t),this.$keepDesiredColumnOnChange=!1,n||(this.$desiredColumn=null)},this.moveCursorToScreen=function(e,t,n){var r=this.session.screenToDocumentPosition(e,t);this.moveCursorTo(r.row,r.column,n)},this.detach=function(){this.lead.detach(),this.anchor.detach(),this.session=this.doc=null},this.fromOrientedRange=function(e){this.setSelectionRange(e,e.cursor==e.start),this.$desiredColumn=e.desiredColumn||this.$desiredColumn},this.toOrientedRange=function(e){var t=this.getRange();return e?(e.start.column=t.start.column,e.start.row=t.start.row,e.end.column=t.end.column,e.end.row=t.end.row):e=t,e.cursor=this.isBackwards()?e.start:e.end,e.desiredColumn=this.$desiredColumn,e},this.getRangeOfMovements=function(e){var t=this.getCursor();try{e(this);var n=this.getCursor();return o.fromPoints(t,n)}catch(r){return o.fromPoints(t,t)}finally{this.moveCursorToPosition(t)}},this.toJSON=function(){if(this.rangeCount)var e=this.ranges.map(function(e){var t=e.clone();return t.isBackwards=e.cursor==e.start,t});else{var e=this.getRange();e.isBackwards=this.isBackwards()}return e},this.fromJSON=function(e){if(e.start==undefined){if(this.rangeList&&e.length>1){this.toSingleRange(e[0]);for(var t=e.length;t--;){var n=o.fromPoints(e[t].start,e[t].end);e[t].isBackwards&&(n.cursor=n.start),this.addRange(n,!0)}return}e=e[0]}this.rangeList&&this.toSingleRange(e),this.setSelectionRange(e,e.isBackwards)},this.isEqual=function(e){if((e.length||this.rangeCount)&&e.length!=this.rangeCount)return!1;if(!e.length||!this.ranges)return this.getRange().isEqual(e);for(var t=this.ranges.length;t--;)if(!this.ranges[t].isEqual(e[t]))return!1;return!0}}).call(u.prototype),t.Selection=u}),ace.define("ace/tokenizer",["require","exports","module","ace/config"],function(e,t,n){"use strict";var r=e("./config"),i=2e3,s=function(e){this.states=e,this.regExps={},this.matchMappings={};for(var t in this.states){var n=this.states[t],r=[],i=0,s=this.matchMappings[t]={defaultToken:"text"},o="g",u=[];for(var a=0;a1?f.onMatch=this.$applyToken:f.onMatch=f.token),c>1&&(/\\\d/.test(f.regex)?l=f.regex.replace(/\\([0-9]+)/g,function(e,t){return"\\"+(parseInt(t,10)+i+1)}):(c=1,l=this.removeCapturingGroups(f.regex)),!f.splitRegex&&typeof f.token!="string"&&u.push(f)),s[i]=a,i+=c,r.push(l),f.onMatch||(f.onMatch=null)}r.length||(s[0]=0,r.push("$")),u.forEach(function(e){e.splitRegex=this.createSplitterRegexp(e.regex,o)},this),this.regExps[t]=new RegExp("("+r.join(")|(")+")|($)",o)}};(function(){this.$setMaxTokenCount=function(e){i=e|0},this.$applyToken=function(e){var t=this.splitRegex.exec(e).slice(1),n=this.token.apply(this,t);if(typeof n=="string")return[{type:n,value:e}];var r=[];for(var i=0,s=n.length;il){var g=e.substring(l,m-v.length);h.type==p?h.value+=g:(h.type&&f.push(h),h={type:p,value:g})}for(var y=0;yi){c>2*e.length&&this.reportError("infinite loop with in ace tokenizer",{startState:t,line:e});while(l1&&n[0]!==r&&n.unshift("#tmp",r),{tokens:f,state:n.length?n:r}},this.reportError=r.reportError}).call(s.prototype),t.Tokenizer=s}),ace.define("ace/mode/text_highlight_rules",["require","exports","module","ace/lib/lang"],function(e,t,n){"use strict";var r=e("../lib/lang"),i=function(){this.$rules={start:[{token:"empty_line",regex:"^$"},{defaultToken:"text"}]}};(function(){this.addRules=function(e,t){if(!t){for(var n in e)this.$rules[n]=e[n];return}for(var n in e){var r=e[n];for(var i=0;i=this.$rowTokens.length){this.$row+=1,e||(e=this.$session.getLength());if(this.$row>=e)return this.$row=e-1,null;this.$rowTokens=this.$session.getTokens(this.$row),this.$tokenIndex=0}return this.$rowTokens[this.$tokenIndex]},this.getCurrentToken=function(){return this.$rowTokens[this.$tokenIndex]},this.getCurrentTokenRow=function(){return this.$row},this.getCurrentTokenColumn=function(){var e=this.$rowTokens,t=this.$tokenIndex,n=e[t].start;if(n!==undefined)return n;n=0;while(t>0)t-=1,n+=e[t].value.length;return n},this.getCurrentTokenPosition=function(){return{row:this.$row,column:this.getCurrentTokenColumn()}},this.getCurrentTokenRange=function(){var e=this.$rowTokens[this.$tokenIndex],t=this.getCurrentTokenColumn();return new r(this.$row,t,this.$row,t+e.value.length)}}).call(i.prototype),t.TokenIterator=i}),ace.define("ace/mode/behaviour/cstyle",["require","exports","module","ace/lib/oop","ace/mode/behaviour","ace/token_iterator","ace/lib/lang"],function(e,t,n){"use strict";var r=e("../../lib/oop"),i=e("../behaviour").Behaviour,s=e("../../token_iterator").TokenIterator,o=e("../../lib/lang"),u=["text","paren.rparen","punctuation.operator"],a=["text","paren.rparen","punctuation.operator","comment"],f,l={},c={'"':'"',"'":"'"},h=function(e){var t=-1;e.multiSelect&&(t=e.selection.index,l.rangeCount!=e.multiSelect.rangeCount&&(l={rangeCount:e.multiSelect.rangeCount}));if(l[t])return f=l[t];f=l[t]={autoInsertedBrackets:0,autoInsertedRow:-1,autoInsertedLineEnd:"",maybeInsertedBrackets:0,maybeInsertedRow:-1,maybeInsertedLineStart:"",maybeInsertedLineEnd:""}},p=function(e,t,n,r){var i=e.end.row-e.start.row;return{text:n+t+r,selection:[0,e.start.column+1,i,e.end.column+(i?0:1)]}},d=function(e){this.add("braces","insertion",function(t,n,r,i,s){var u=r.getCursorPosition(),a=i.doc.getLine(u.row);if(s=="{"){h(r);var l=r.getSelectionRange(),c=i.doc.getTextRange(l);if(c!==""&&c!=="{"&&r.getWrapBehavioursEnabled())return p(l,c,"{","}");if(d.isSaneInsertion(r,i))return/[\]\}\)]/.test(a[u.column])||r.inMultiSelectMode||e&&e.braces?(d.recordAutoInsert(r,i,"}"),{text:"{}",selection:[1,1]}):(d.recordMaybeInsert(r,i,"{"),{text:"{",selection:[1,1]})}else if(s=="}"){h(r);var v=a.substring(u.column,u.column+1);if(v=="}"){var m=i.$findOpeningBracket("}",{column:u.column+1,row:u.row});if(m!==null&&d.isAutoInsertedClosing(u,a,s))return d.popAutoInsertedClosing(),{text:"",selection:[1,1]}}}else{if(s=="\n"||s=="\r\n"){h(r);var g="";d.isMaybeInsertedClosing(u,a)&&(g=o.stringRepeat("}",f.maybeInsertedBrackets),d.clearMaybeInsertedClosing());var v=a.substring(u.column,u.column+1);if(v==="}"){var y=i.findMatchingBracket({row:u.row,column:u.column+1},"}");if(!y)return null;var b=this.$getIndent(i.getLine(y.row))}else{if(!g){d.clearMaybeInsertedClosing();return}var b=this.$getIndent(a)}var w=b+i.getTabString();return{text:"\n"+w+"\n"+b+g,selection:[1,w.length,1,w.length]}}d.clearMaybeInsertedClosing()}}),this.add("braces","deletion",function(e,t,n,r,i){var s=r.doc.getTextRange(i);if(!i.isMultiLine()&&s=="{"){h(n);var o=r.doc.getLine(i.start.row),u=o.substring(i.end.column,i.end.column+1);if(u=="}")return i.end.column++,i;f.maybeInsertedBrackets--}}),this.add("parens","insertion",function(e,t,n,r,i){if(i=="("){h(n);var s=n.getSelectionRange(),o=r.doc.getTextRange(s);if(o!==""&&n.getWrapBehavioursEnabled())return p(s,o,"(",")");if(d.isSaneInsertion(n,r))return d.recordAutoInsert(n,r,")"),{text:"()",selection:[1,1]}}else if(i==")"){h(n);var u=n.getCursorPosition(),a=r.doc.getLine(u.row),f=a.substring(u.column,u.column+1);if(f==")"){var l=r.$findOpeningBracket(")",{column:u.column+1,row:u.row});if(l!==null&&d.isAutoInsertedClosing(u,a,i))return d.popAutoInsertedClosing(),{text:"",selection:[1,1]}}}}),this.add("parens","deletion",function(e,t,n,r,i){var s=r.doc.getTextRange(i);if(!i.isMultiLine()&&s=="("){h(n);var o=r.doc.getLine(i.start.row),u=o.substring(i.start.column+1,i.start.column+2);if(u==")")return i.end.column++,i}}),this.add("brackets","insertion",function(e,t,n,r,i){if(i=="["){h(n);var s=n.getSelectionRange(),o=r.doc.getTextRange(s);if(o!==""&&n.getWrapBehavioursEnabled())return p(s,o,"[","]");if(d.isSaneInsertion(n,r))return d.recordAutoInsert(n,r,"]"),{text:"[]",selection:[1,1]}}else if(i=="]"){h(n);var u=n.getCursorPosition(),a=r.doc.getLine(u.row),f=a.substring(u.column,u.column+1);if(f=="]"){var l=r.$findOpeningBracket("]",{column:u.column+1,row:u.row});if(l!==null&&d.isAutoInsertedClosing(u,a,i))return d.popAutoInsertedClosing(),{text:"",selection:[1,1]}}}}),this.add("brackets","deletion",function(e,t,n,r,i){var s=r.doc.getTextRange(i);if(!i.isMultiLine()&&s=="["){h(n);var o=r.doc.getLine(i.start.row),u=o.substring(i.start.column+1,i.start.column+2);if(u=="]")return i.end.column++,i}}),this.add("string_dquotes","insertion",function(e,t,n,r,i){var s=r.$mode.$quotes||c;if(i.length==1&&s[i]){if(this.lineCommentStart&&this.lineCommentStart.indexOf(i)!=-1)return;h(n);var o=i,u=n.getSelectionRange(),a=r.doc.getTextRange(u);if(a!==""&&(a.length!=1||!s[a])&&n.getWrapBehavioursEnabled())return p(u,a,o,o);if(!a){var f=n.getCursorPosition(),l=r.doc.getLine(f.row),d=l.substring(f.column-1,f.column),v=l.substring(f.column,f.column+1),m=r.getTokenAt(f.row,f.column),g=r.getTokenAt(f.row,f.column+1);if(d=="\\"&&m&&/escape/.test(m.type))return null;var y=m&&/string|escape/.test(m.type),b=!g||/string|escape/.test(g.type),w;if(v==o)w=y!==b,w&&/string\.end/.test(g.type)&&(w=!1);else{if(y&&!b)return null;if(y&&b)return null;var E=r.$mode.tokenRe;E.lastIndex=0;var S=E.test(d);E.lastIndex=0;var x=E.test(d);if(S||x)return null;if(v&&!/[\s;,.})\]\\]/.test(v))return null;var T=l[f.column-2];if(!(d!=o||T!=o&&!E.test(T)))return null;w=!0}return{text:w?o+o:"",selection:[1,1]}}}}),this.add("string_dquotes","deletion",function(e,t,n,r,i){var s=r.$mode.$quotes||c,o=r.doc.getTextRange(i);if(!i.isMultiLine()&&s.hasOwnProperty(o)){h(n);var u=r.doc.getLine(i.start.row),a=u.substring(i.start.column+1,i.start.column+2);if(a==o)return i.end.column++,i}})};d.isSaneInsertion=function(e,t){var n=e.getCursorPosition(),r=new s(t,n.row,n.column);if(!this.$matchTokenType(r.getCurrentToken()||"text",u)){var i=new s(t,n.row,n.column+1);if(!this.$matchTokenType(i.getCurrentToken()||"text",u))return!1}return r.stepForward(),r.getCurrentTokenRow()!==n.row||this.$matchTokenType(r.getCurrentToken()||"text",a)},d.$matchTokenType=function(e,t){return t.indexOf(e.type||e)>-1},d.recordAutoInsert=function(e,t,n){var r=e.getCursorPosition(),i=t.doc.getLine(r.row);this.isAutoInsertedClosing(r,i,f.autoInsertedLineEnd[0])||(f.autoInsertedBrackets=0),f.autoInsertedRow=r.row,f.autoInsertedLineEnd=n+i.substr(r.column),f.autoInsertedBrackets++},d.recordMaybeInsert=function(e,t,n){var r=e.getCursorPosition(),i=t.doc.getLine(r.row);this.isMaybeInsertedClosing(r,i)||(f.maybeInsertedBrackets=0),f.maybeInsertedRow=r.row,f.maybeInsertedLineStart=i.substr(0,r.column)+n,f.maybeInsertedLineEnd=i.substr(r.column),f.maybeInsertedBrackets++},d.isAutoInsertedClosing=function(e,t,n){return f.autoInsertedBrackets>0&&e.row===f.autoInsertedRow&&n===f.autoInsertedLineEnd[0]&&t.substr(e.column)===f.autoInsertedLineEnd},d.isMaybeInsertedClosing=function(e,t){return f.maybeInsertedBrackets>0&&e.row===f.maybeInsertedRow&&t.substr(e.column)===f.maybeInsertedLineEnd&&t.substr(0,e.column)==f.maybeInsertedLineStart},d.popAutoInsertedClosing=function(){f.autoInsertedLineEnd=f.autoInsertedLineEnd.substr(1),f.autoInsertedBrackets--},d.clearMaybeInsertedClosing=function(){f&&(f.maybeInsertedBrackets=0,f.maybeInsertedRow=-1)},r.inherits(d,i),t.CstyleBehaviour=d}),ace.define("ace/unicode",["require","exports","module"],function(e,t,n){"use strict";var r=[48,9,8,25,5,0,2,25,48,0,11,0,5,0,6,22,2,30,2,457,5,11,15,4,8,0,2,0,18,116,2,1,3,3,9,0,2,2,2,0,2,19,2,82,2,138,2,4,3,155,12,37,3,0,8,38,10,44,2,0,2,1,2,1,2,0,9,26,6,2,30,10,7,61,2,9,5,101,2,7,3,9,2,18,3,0,17,58,3,100,15,53,5,0,6,45,211,57,3,18,2,5,3,11,3,9,2,1,7,6,2,2,2,7,3,1,3,21,2,6,2,0,4,3,3,8,3,1,3,3,9,0,5,1,2,4,3,11,16,2,2,5,5,1,3,21,2,6,2,1,2,1,2,1,3,0,2,4,5,1,3,2,4,0,8,3,2,0,8,15,12,2,2,8,2,2,2,21,2,6,2,1,2,4,3,9,2,2,2,2,3,0,16,3,3,9,18,2,2,7,3,1,3,21,2,6,2,1,2,4,3,8,3,1,3,2,9,1,5,1,2,4,3,9,2,0,17,1,2,5,4,2,2,3,4,1,2,0,2,1,4,1,4,2,4,11,5,4,4,2,2,3,3,0,7,0,15,9,18,2,2,7,2,2,2,22,2,9,2,4,4,7,2,2,2,3,8,1,2,1,7,3,3,9,19,1,2,7,2,2,2,22,2,9,2,4,3,8,2,2,2,3,8,1,8,0,2,3,3,9,19,1,2,7,2,2,2,22,2,15,4,7,2,2,2,3,10,0,9,3,3,9,11,5,3,1,2,17,4,23,2,8,2,0,3,6,4,0,5,5,2,0,2,7,19,1,14,57,6,14,2,9,40,1,2,0,3,1,2,0,3,0,7,3,2,6,2,2,2,0,2,0,3,1,2,12,2,2,3,4,2,0,2,5,3,9,3,1,35,0,24,1,7,9,12,0,2,0,2,0,5,9,2,35,5,19,2,5,5,7,2,35,10,0,58,73,7,77,3,37,11,42,2,0,4,328,2,3,3,6,2,0,2,3,3,40,2,3,3,32,2,3,3,6,2,0,2,3,3,14,2,56,2,3,3,66,5,0,33,15,17,84,13,619,3,16,2,25,6,74,22,12,2,6,12,20,12,19,13,12,2,2,2,1,13,51,3,29,4,0,5,1,3,9,34,2,3,9,7,87,9,42,6,69,11,28,4,11,5,11,11,39,3,4,12,43,5,25,7,10,38,27,5,62,2,28,3,10,7,9,14,0,89,75,5,9,18,8,13,42,4,11,71,55,9,9,4,48,83,2,2,30,14,230,23,280,3,5,3,37,3,5,3,7,2,0,2,0,2,0,2,30,3,52,2,6,2,0,4,2,2,6,4,3,3,5,5,12,6,2,2,6,67,1,20,0,29,0,14,0,17,4,60,12,5,0,4,11,18,0,5,0,3,9,2,0,4,4,7,0,2,0,2,0,2,3,2,10,3,3,6,4,5,0,53,1,2684,46,2,46,2,132,7,6,15,37,11,53,10,0,17,22,10,6,2,6,2,6,2,6,2,6,2,6,2,6,2,6,2,31,48,0,470,1,36,5,2,4,6,1,5,85,3,1,3,2,2,89,2,3,6,40,4,93,18,23,57,15,513,6581,75,20939,53,1164,68,45,3,268,4,27,21,31,3,13,13,1,2,24,9,69,11,1,38,8,3,102,3,1,111,44,25,51,13,68,12,9,7,23,4,0,5,45,3,35,13,28,4,64,15,10,39,54,10,13,3,9,7,22,4,1,5,66,25,2,227,42,2,1,3,9,7,11171,13,22,5,48,8453,301,3,61,3,105,39,6,13,4,6,11,2,12,2,4,2,0,2,1,2,1,2,107,34,362,19,63,3,53,41,11,5,15,17,6,13,1,25,2,33,4,2,134,20,9,8,25,5,0,2,25,12,88,4,5,3,5,3,5,3,2],i=0,s=[];for(var o=0;o2?r%f!=f-1:r%f==0}}var E=Infinity;w(function(e,t){var n=e.search(/\S/);n!==-1?(ne.length&&(E=e.length)}),u==Infinity&&(u=E,s=!1,o=!1),l&&u%f!=0&&(u=Math.floor(u/f)*f),w(o?m:v)},this.toggleBlockComment=function(e,t,n,r){var i=this.blockComment;if(!i)return;!i.start&&i[0]&&(i=i[0]);var s=new f(t,r.row,r.column),o=s.getCurrentToken(),u=t.selection,a=t.selection.toOrientedRange(),c,h;if(o&&/comment/.test(o.type)){var p,d;while(o&&/comment/.test(o.type)){var v=o.value.indexOf(i.start);if(v!=-1){var m=s.getCurrentTokenRow(),g=s.getCurrentTokenColumn()+v;p=new l(m,g,m,g+i.start.length);break}o=s.stepBackward()}var s=new f(t,r.row,r.column),o=s.getCurrentToken();while(o&&/comment/.test(o.type)){var v=o.value.indexOf(i.end);if(v!=-1){var m=s.getCurrentTokenRow(),g=s.getCurrentTokenColumn()+v;d=new l(m,g,m,g+i.end.length);break}o=s.stepForward()}d&&t.remove(d),p&&(t.remove(p),c=p.start.row,h=-i.start.length)}else h=i.start.length,c=n.start.row,t.insert(n.end,i.end),t.insert(n.start,i.start);a.start.row==c&&(a.start.column+=h),a.end.row==c&&(a.end.column+=h),t.selection.fromOrientedRange(a)},this.getNextLineIndent=function(e,t,n){return this.$getIndent(t)},this.checkOutdent=function(e,t,n){return!1},this.autoOutdent=function(e,t,n){},this.$getIndent=function(e){return e.match(/^\s*/)[0]},this.createWorker=function(e){return null},this.createModeDelegates=function(e){this.$embeds=[],this.$modes={};for(var t in e)if(e[t]){var n=e[t],i=n.prototype.$id,s=r.$modes[i];s||(r.$modes[i]=s=new n),r.$modes[t]||(r.$modes[t]=s),this.$embeds.push(t),this.$modes[t]=s}var o=["toggleBlockComment","toggleCommentLines","getNextLineIndent","checkOutdent","autoOutdent","transformAction","getCompletions"];for(var t=0;t=0&&t.row=0&&t.column<=e[t.row].length}function s(e,t){t.action!="insert"&&t.action!="remove"&&r(t,"delta.action must be 'insert' or 'remove'"),t.lines instanceof Array||r(t,"delta.lines must be an Array"),(!t.start||!t.end)&&r(t,"delta.start/end must be an present");var n=t.start;i(e,t.start)||r(t,"delta.start must be contained in document");var s=t.end;t.action=="remove"&&!i(e,s)&&r(t,"delta.end must contained in document for 'remove' actions");var o=s.row-n.row,u=s.column-(o==0?n.column:0);(o!=t.lines.length-1||t.lines[o].length!=u)&&r(t,"delta.range must match delta lines")}t.applyDelta=function(e,t,n){var r=t.start.row,i=t.start.column,s=e[r]||"";switch(t.action){case"insert":var o=t.lines;if(o.length===1)e[r]=s.substring(0,i)+t.lines[0]+s.substring(i);else{var u=[r,1].concat(t.lines);e.splice.apply(e,u),e[r]=s.substring(0,i)+e[r],e[r+t.lines.length-1]+=s.substring(i)}break;case"remove":var a=t.end.column,f=t.end.row;r===f?e[r]=s.substring(0,i)+s.substring(a):e.splice(r,f-r+1,s.substring(0,i)+e[f].substring(a))}}}),ace.define("ace/anchor",["require","exports","module","ace/lib/oop","ace/lib/event_emitter"],function(e,t,n){"use strict";var r=e("./lib/oop"),i=e("./lib/event_emitter").EventEmitter,s=t.Anchor=function(e,t,n){this.$onChange=this.onChange.bind(this),this.attach(e),typeof n=="undefined"?this.setPosition(t.row,t.column):this.setPosition(t,n)};(function(){function e(e,t,n){var r=n?e.column<=t.column:e.columnthis.row)return;var n=t(e,{row:this.row,column:this.column},this.$insertRight);this.setPosition(n.row,n.column,!0)},this.setPosition=function(e,t,n){var r;n?r={row:e,column:t}:r=this.$clipPositionToDocument(e,t);if(this.row==r.row&&this.column==r.column)return;var i={row:this.row,column:this.column};this.row=r.row,this.column=r.column,this._signal("change",{old:i,value:r})},this.detach=function(){this.document.removeEventListener("change",this.$onChange)},this.attach=function(e){this.document=e||this.document,this.document.on("change",this.$onChange)},this.$clipPositionToDocument=function(e,t){var n={};return e>=this.document.getLength()?(n.row=Math.max(0,this.document.getLength()-1),n.column=this.document.getLine(n.row).length):e<0?(n.row=0,n.column=0):(n.row=e,n.column=Math.min(this.document.getLine(n.row).length,Math.max(0,t))),t<0&&(n.column=0),n}}).call(s.prototype)}),ace.define("ace/document",["require","exports","module","ace/lib/oop","ace/apply_delta","ace/lib/event_emitter","ace/range","ace/anchor"],function(e,t,n){"use strict";var r=e("./lib/oop"),i=e("./apply_delta").applyDelta,s=e("./lib/event_emitter").EventEmitter,o=e("./range").Range,u=e("./anchor").Anchor,a=function(e){this.$lines=[""],e.length===0?this.$lines=[""]:Array.isArray(e)?this.insertMergedLines({row:0,column:0},e):this.insert({row:0,column:0},e)};(function(){r.implement(this,s),this.setValue=function(e){var t=this.getLength()-1;this.remove(new o(0,0,t,this.getLine(t).length)),this.insert({row:0,column:0},e)},this.getValue=function(){return this.getAllLines().join(this.getNewLineCharacter())},this.createAnchor=function(e,t){return new u(this,e,t)},"aaa".split(/a/).length===0?this.$split=function(e){return e.replace(/\r\n|\r/g,"\n").split("\n")}:this.$split=function(e){return e.split(/\r\n|\r|\n/)},this.$detectNewLine=function(e){var t=e.match(/^.*?(\r\n|\r|\n)/m);this.$autoNewLine=t?t[1]:"\n",this._signal("changeNewLineMode")},this.getNewLineCharacter=function(){switch(this.$newLineMode){case"windows":return"\r\n";case"unix":return"\n";default:return this.$autoNewLine||"\n"}},this.$autoNewLine="",this.$newLineMode="auto",this.setNewLineMode=function(e){if(this.$newLineMode===e)return;this.$newLineMode=e,this._signal("changeNewLineMode")},this.getNewLineMode=function(){return this.$newLineMode},this.isNewLine=function(e){return e=="\r\n"||e=="\r"||e=="\n"},this.getLine=function(e){return this.$lines[e]||""},this.getLines=function(e,t){return this.$lines.slice(e,t+1)},this.getAllLines=function(){return this.getLines(0,this.getLength())},this.getLength=function(){return this.$lines.length},this.getTextRange=function(e){return this.getLinesForRange(e).join(this.getNewLineCharacter())},this.getLinesForRange=function(e){var t;if(e.start.row===e.end.row)t=[this.getLine(e.start.row).substring(e.start.column,e.end.column)];else{t=this.getLines(e.start.row,e.end.row),t[0]=(t[0]||"").substring(e.start.column);var n=t.length-1;e.end.row-e.start.row==n&&(t[n]=t[n].substring(0,e.end.column))}return t},this.insertLines=function(e,t){return console.warn("Use of document.insertLines is deprecated. Use the insertFullLines method instead."),this.insertFullLines(e,t)},this.removeLines=function(e,t){return console.warn("Use of document.removeLines is deprecated. Use the removeFullLines method instead."),this.removeFullLines(e,t)},this.insertNewLine=function(e){return console.warn("Use of document.insertNewLine is deprecated. Use insertMergedLines(position, ['', '']) instead."),this.insertMergedLines(e,["",""])},this.insert=function(e,t){return this.getLength()<=1&&this.$detectNewLine(t),this.insertMergedLines(e,this.$split(t))},this.insertInLine=function(e,t){var n=this.clippedPos(e.row,e.column),r=this.pos(e.row,e.column+t.length);return this.applyDelta({start:n,end:r,action:"insert",lines:[t]},!0),this.clonePos(r)},this.clippedPos=function(e,t){var n=this.getLength();e===undefined?e=n:e<0?e=0:e>=n&&(e=n-1,t=undefined);var r=this.getLine(e);return t==undefined&&(t=r.length),t=Math.min(Math.max(t,0),r.length),{row:e,column:t}},this.clonePos=function(e){return{row:e.row,column:e.column}},this.pos=function(e,t){return{row:e,column:t}},this.$clipPosition=function(e){var t=this.getLength();return e.row>=t?(e.row=Math.max(0,t-1),e.column=this.getLine(t-1).length):(e.row=Math.max(0,e.row),e.column=Math.min(Math.max(e.column,0),this.getLine(e.row).length)),e},this.insertFullLines=function(e,t){e=Math.min(Math.max(e,0),this.getLength());var n=0;e0,r=t=0&&this.applyDelta({start:this.pos(e,this.getLine(e).length),end:this.pos(e+1,0),action:"remove",lines:["",""]})},this.replace=function(e,t){e instanceof o||(e=o.fromPoints(e.start,e.end));if(t.length===0&&e.isEmpty())return e.start;if(t==this.getTextRange(e))return e.end;this.remove(e);var n;return t?n=this.insert(e.start,t):n=e.start,n},this.applyDeltas=function(e){for(var t=0;t=0;t--)this.revertDelta(e[t])},this.applyDelta=function(e,t){var n=e.action=="insert";if(n?e.lines.length<=1&&!e.lines[0]:!o.comparePoints(e.start,e.end))return;n&&e.lines.length>2e4?this.$splitAndapplyLargeDelta(e,2e4):(i(this.$lines,e,t),this._signal("change",e))},this.$splitAndapplyLargeDelta=function(e,t){var n=e.lines,r=n.length-t+1,i=e.start.row,s=e.start.column;for(var o=0,u=0;o20){n.running=setTimeout(n.$worker,20);break}}n.currentLine=t,r==-1&&(r=t),s<=r&&n.fireUpdateEvent(s,r)}};(function(){r.implement(this,i),this.setTokenizer=function(e){this.tokenizer=e,this.lines=[],this.states=[],this.start(0)},this.setDocument=function(e){this.doc=e,this.lines=[],this.states=[],this.stop()},this.fireUpdateEvent=function(e,t){var n={first:e,last:t};this._signal("update",{data:n})},this.start=function(e){this.currentLine=Math.min(e||0,this.currentLine,this.doc.getLength()),this.lines.splice(this.currentLine,this.lines.length),this.states.splice(this.currentLine,this.states.length),this.stop(),this.running=setTimeout(this.$worker,700)},this.scheduleStart=function(){this.running||(this.running=setTimeout(this.$worker,700))},this.$updateOnChange=function(e){var t=e.start.row,n=e.end.row-t;if(n===0)this.lines[t]=null;else if(e.action=="remove")this.lines.splice(t,n+1,null),this.states.splice(t,n+1,null);else{var r=Array(n+1);r.unshift(t,1),this.lines.splice.apply(this.lines,r),this.states.splice.apply(this.states,r)}this.currentLine=Math.min(t,this.currentLine,this.doc.getLength()),this.stop()},this.stop=function(){this.running&&clearTimeout(this.running),this.running=!1},this.getTokens=function(e){return this.lines[e]||this.$tokenizeRow(e)},this.getState=function(e){return this.currentLine==e&&this.$tokenizeRow(e),this.states[e]||"start"},this.$tokenizeRow=function(e){var t=this.doc.getLine(e),n=this.states[e-1],r=this.tokenizer.getLineTokens(t,n,e);return this.states[e]+""!=r.state+""?(this.states[e]=r.state,this.lines[e+1]=null,this.currentLine>e+1&&(this.currentLine=e+1)):this.currentLine==e&&(this.currentLine=e+1),this.lines[e]=r.tokens}}).call(s.prototype),t.BackgroundTokenizer=s}),ace.define("ace/search_highlight",["require","exports","module","ace/lib/lang","ace/lib/oop","ace/range"],function(e,t,n){"use strict";var r=e("./lib/lang"),i=e("./lib/oop"),s=e("./range").Range,o=function(e,t,n){this.setRegexp(e),this.clazz=t,this.type=n||"text"};(function(){this.MAX_RANGES=500,this.setRegexp=function(e){if(this.regExp+""==e+"")return;this.regExp=e,this.cache=[]},this.update=function(e,t,n,i){if(!this.regExp)return;var o=i.firstRow,u=i.lastRow;for(var a=o;a<=u;a++){var f=this.cache[a];f==null&&(f=r.getMatchOffsets(n.getLine(a),this.regExp),f.length>this.MAX_RANGES&&(f=f.slice(0,this.MAX_RANGES)),f=f.map(function(e){return new s(a,e.offset,a,e.offset+e.length)}),this.cache[a]=f.length?f:"");for(var l=f.length;l--;)t.drawSingleLineMarker(e,f[l].toScreenRange(n),this.clazz,i)}}}).call(o.prototype),t.SearchHighlight=o}),ace.define("ace/edit_session/fold_line",["require","exports","module","ace/range"],function(e,t,n){"use strict";function i(e,t){this.foldData=e,Array.isArray(t)?this.folds=t:t=this.folds=[t];var n=t[t.length-1];this.range=new r(t[0].start.row,t[0].start.column,n.end.row,n.end.column),this.start=this.range.start,this.end=this.range.end,this.folds.forEach(function(e){e.setFoldLine(this)},this)}var r=e("../range").Range;(function(){this.shiftRow=function(e){this.start.row+=e,this.end.row+=e,this.folds.forEach(function(t){t.start.row+=e,t.end.row+=e})},this.addFold=function(e){if(e.sameRow){if(e.start.rowthis.endRow)throw new Error("Can't add a fold to this FoldLine as it has no connection");this.folds.push(e),this.folds.sort(function(e,t){return-e.range.compareEnd(t.start.row,t.start.column)}),this.range.compareEnd(e.start.row,e.start.column)>0?(this.end.row=e.end.row,this.end.column=e.end.column):this.range.compareStart(e.end.row,e.end.column)<0&&(this.start.row=e.start.row,this.start.column=e.start.column)}else if(e.start.row==this.end.row)this.folds.push(e),this.end.row=e.end.row,this.end.column=e.end.column;else{if(e.end.row!=this.start.row)throw new Error("Trying to add fold to FoldRow that doesn't have a matching row");this.folds.unshift(e),this.start.row=e.start.row,this.start.column=e.start.column}e.foldLine=this},this.containsRow=function(e){return e>=this.start.row&&e<=this.end.row},this.walk=function(e,t,n){var r=0,i=this.folds,s,o,u,a=!0;t==null&&(t=this.end.row,n=this.end.column);for(var f=0;f0)continue;var a=i(e,o.start);return u===0?t&&a!==0?-s-2:s:a>0||a===0&&!t?s:-s-1}return-s-1},this.add=function(e){var t=!e.isEmpty(),n=this.pointIndex(e.start,t);n<0&&(n=-n-1);var r=this.pointIndex(e.end,t,n);return r<0?r=-r-1:r++,this.ranges.splice(n,r-n,e)},this.addList=function(e){var t=[];for(var n=e.length;n--;)t.push.apply(t,this.add(e[n]));return t},this.substractPoint=function(e){var t=this.pointIndex(e);if(t>=0)return this.ranges.splice(t,1)},this.merge=function(){var e=[],t=this.ranges;t=t.sort(function(e,t){return i(e.start,t.start)});var n=t[0],r;for(var s=1;s=0},this.containsPoint=function(e){return this.pointIndex(e)>=0},this.rangeAtPoint=function(e){var t=this.pointIndex(e);if(t>=0)return this.ranges[t]},this.clipRows=function(e,t){var n=this.ranges;if(n[0].start.row>t||n[n.length-1].start.row=r)break}if(e.action=="insert"){var f=i-r,l=-t.column+n.column;for(;or)break;a.start.row==r&&a.start.column>=t.column&&(a.start.column!=t.column||!this.$insertRight)&&(a.start.column+=l,a.start.row+=f);if(a.end.row==r&&a.end.column>=t.column){if(a.end.column==t.column&&this.$insertRight)continue;a.end.column==t.column&&l>0&&oa.start.column&&a.end.column==s[o+1].start.column&&(a.end.column-=l),a.end.column+=l,a.end.row+=f}}}else{var f=r-i,l=t.column-n.column;for(;oi)break;if(a.end.rowt.column)a.end.column=t.column,a.end.row=t.row}else a.end.column+=l,a.end.row+=f;else a.end.row>i&&(a.end.row+=f);if(a.start.rowt.column)a.start.column=t.column,a.start.row=t.row}else a.start.column+=l,a.start.row+=f;else a.start.row>i&&(a.start.row+=f)}}if(f!=0&&o=e)return i;if(i.end.row>e)return null}return null},this.getNextFoldLine=function(e,t){var n=this.$foldData,r=0;t&&(r=n.indexOf(t)),r==-1&&(r=0);for(r;r=e)return i}return null},this.getFoldedRowCount=function(e,t){var n=this.$foldData,r=t-e+1;for(var i=0;i=t){u=e?r-=t-u:r=0);break}o>=e&&(u>=e?r-=o-u:r-=o-e+1)}return r},this.$addFoldLine=function(e){return this.$foldData.push(e),this.$foldData.sort(function(e,t){return e.start.row-t.start.row}),e},this.addFold=function(e,t){var n=this.$foldData,r=!1,o;e instanceof s?o=e:(o=new s(t,e),o.collapseChildren=t.collapseChildren),this.$clipRangeToDocument(o.range);var u=o.start.row,a=o.start.column,f=o.end.row,l=o.end.column,c=this.getFoldAt(u,a,1),h=this.getFoldAt(f,l,-1);if(c&&h==c)return c.addSubFold(o);c&&!c.range.isStart(u,a)&&this.removeFold(c),h&&!h.range.isEnd(f,l)&&this.removeFold(h);var p=this.getFoldsInRange(o.range);p.length>0&&(this.removeFolds(p),p.forEach(function(e){o.addSubFold(e)}));for(var d=0;d0&&this.foldAll(e.start.row+1,e.end.row,e.collapseChildren-1),e.subFolds=[]},this.expandFolds=function(e){e.forEach(function(e){this.expandFold(e)},this)},this.unfold=function(e,t){var n,i;e==null?(n=new r(0,0,this.getLength(),0),t=!0):typeof e=="number"?n=new r(e,0,e,this.getLine(e).length):"row"in e?n=r.fromPoints(e,e):n=e,i=this.getFoldsInRangeList(n);if(t)this.removeFolds(i);else{var s=i;while(s.length)this.expandFolds(s),s=this.getFoldsInRangeList(n)}if(i.length)return i},this.isRowFolded=function(e,t){return!!this.getFoldLine(e,t)},this.getRowFoldEnd=function(e,t){var n=this.getFoldLine(e,t);return n?n.end.row:e},this.getRowFoldStart=function(e,t){var n=this.getFoldLine(e,t);return n?n.start.row:e},this.getFoldDisplayLine=function(e,t,n,r,i){r==null&&(r=e.start.row),i==null&&(i=0),t==null&&(t=e.end.row),n==null&&(n=this.getLine(t).length);var s=this.doc,o="";return e.walk(function(e,t,n,u){if(tl)break}while(s&&a.test(s.type));s=i.stepBackward()}else s=i.getCurrentToken();return f.end.row=i.getCurrentTokenRow(),f.end.column=i.getCurrentTokenColumn()+s.value.length-2,f}},this.foldAll=function(e,t,n){n==undefined&&(n=1e5);var r=this.foldWidgets;if(!r)return;t=t||this.getLength(),e=e||0;for(var i=e;i=e){i=s.end.row;try{var o=this.addFold("...",s);o&&(o.collapseChildren=n)}catch(u){}}}},this.$foldStyles={manual:1,markbegin:1,markbeginend:1},this.$foldStyle="markbegin",this.setFoldStyle=function(e){if(!this.$foldStyles[e])throw new Error("invalid fold style: "+e+"["+Object.keys(this.$foldStyles).join(", ")+"]");if(this.$foldStyle==e)return;this.$foldStyle=e,e=="manual"&&this.unfold();var t=this.$foldMode;this.$setFolding(null),this.$setFolding(t)},this.$setFolding=function(e){if(this.$foldMode==e)return;this.$foldMode=e,this.off("change",this.$updateFoldWidgets),this.off("tokenizerUpdate",this.$tokenizerUpdateFoldWidgets),this._signal("changeAnnotation");if(!e||this.$foldStyle=="manual"){this.foldWidgets=null;return}this.foldWidgets=[],this.getFoldWidget=e.getFoldWidget.bind(e,this,this.$foldStyle),this.getFoldWidgetRange=e.getFoldWidgetRange.bind(e,this,this.$foldStyle),this.$updateFoldWidgets=this.updateFoldWidgets.bind(this),this.$tokenizerUpdateFoldWidgets=this.tokenizerUpdateFoldWidgets.bind(this),this.on("change",this.$updateFoldWidgets),this.on("tokenizerUpdate",this.$tokenizerUpdateFoldWidgets)},this.getParentFoldRangeData=function(e,t){var n=this.foldWidgets;if(!n||t&&n[e])return{};var r=e-1,i;while(r>=0){var s=n[r];s==null&&(s=n[r]=this.getFoldWidget(r));if(s=="start"){var o=this.getFoldWidgetRange(r);i||(i=o);if(o&&o.end.row>=e)break}r--}return{range:r!==-1&&o,firstRange:i}},this.onFoldWidgetClick=function(e,t){t=t.domEvent;var n={children:t.shiftKey,all:t.ctrlKey||t.metaKey,siblings:t.altKey},r=this.$toggleFoldWidget(e,n);if(!r){var i=t.target||t.srcElement;i&&/ace_fold-widget/.test(i.className)&&(i.className+=" ace_invalid")}},this.$toggleFoldWidget=function(e,t){if(!this.getFoldWidget)return;var n=this.getFoldWidget(e),r=this.getLine(e),i=n==="end"?-1:1,s=this.getFoldAt(e,i===-1?0:r.length,i);if(s)return t.children||t.all?this.removeFold(s):this.expandFold(s),s;var o=this.getFoldWidgetRange(e,!0);if(o&&!o.isMultiLine()){s=this.getFoldAt(o.start.row,o.start.column,1);if(s&&o.isEqual(s.range))return this.removeFold(s),s}if(t.siblings){var u=this.getParentFoldRangeData(e);if(u.range)var a=u.range.start.row+1,f=u.range.end.row;this.foldAll(a,f,t.all?1e4:0)}else t.children?(f=o?o.end.row:this.getLength(),this.foldAll(e+1,f,t.all?1e4:0)):o&&(t.all&&(o.collapseChildren=1e4),this.addFold("...",o));return o},this.toggleFoldWidget=function(e){var t=this.selection.getCursor().row;t=this.getRowFoldStart(t);var n=this.$toggleFoldWidget(t,{});if(n)return;var r=this.getParentFoldRangeData(t,!0);n=r.range||r.firstRange;if(n){t=n.start.row;var i=this.getFoldAt(t,this.getLine(t).length,1);i?this.removeFold(i):this.addFold("...",n)}},this.updateFoldWidgets=function(e){var t=e.start.row,n=e.end.row-t;if(n===0)this.foldWidgets[t]=null;else if(e.action=="remove")this.foldWidgets.splice(t,n+1,null);else{var r=Array(n+1);r.unshift(t,1),this.foldWidgets.splice.apply(this.foldWidgets,r)}},this.tokenizerUpdateFoldWidgets=function(e){var t=e.data;t.first!=t.last&&this.foldWidgets.length>t.first&&this.foldWidgets.splice(t.first,this.foldWidgets.length)}}var r=e("../range").Range,i=e("./fold_line").FoldLine,s=e("./fold").Fold,o=e("../token_iterator").TokenIterator;t.Folding=u}),ace.define("ace/edit_session/bracket_match",["require","exports","module","ace/token_iterator","ace/range"],function(e,t,n){"use strict";function s(){this.findMatchingBracket=function(e,t){if(e.column==0)return null;var n=t||this.getLine(e.row).charAt(e.column-1);if(n=="")return null;var r=n.match(/([\(\[\{])|([\)\]\}])/);return r?r[1]?this.$findClosingBracket(r[1],e):this.$findOpeningBracket(r[2],e):null},this.getBracketRange=function(e){var t=this.getLine(e.row),n=!0,r,s=t.charAt(e.column-1),o=s&&s.match(/([\(\[\{])|([\)\]\}])/);o||(s=t.charAt(e.column),e={row:e.row,column:e.column+1},o=s&&s.match(/([\(\[\{])|([\)\]\}])/),n=!1);if(!o)return null;if(o[1]){var u=this.$findClosingBracket(o[1],e);if(!u)return null;r=i.fromPoints(e,u),n||(r.end.column++,r.start.column--),r.cursor=r.end}else{var u=this.$findOpeningBracket(o[2],e);if(!u)return null;r=i.fromPoints(u,e),n||(r.start.column++,r.end.column--),r.cursor=r.start}return r},this.$brackets={")":"(","(":")","]":"[","[":"]","{":"}","}":"{","<":">",">":"<"},this.$findOpeningBracket=function(e,t,n){var i=this.$brackets[e],s=1,o=new r(this,t.row,t.column),u=o.getCurrentToken();u||(u=o.stepForward());if(!u)return;n||(n=new RegExp("(\\.?"+u.type.replace(".","\\.").replace("rparen",".paren").replace(/\b(?:end)\b/,"(?:start|begin|end)")+")+"));var a=t.column-o.getCurrentTokenColumn()-2,f=u.value;for(;;){while(a>=0){var l=f.charAt(a);if(l==i){s-=1;if(s==0)return{row:o.getCurrentTokenRow(),column:a+o.getCurrentTokenColumn()}}else l==e&&(s+=1);a-=1}do u=o.stepBackward();while(u&&!n.test(u.type));if(u==null)break;f=u.value,a=f.length-1}return null},this.$findClosingBracket=function(e,t,n){var i=this.$brackets[e],s=1,o=new r(this,t.row,t.column),u=o.getCurrentToken();u||(u=o.stepForward());if(!u)return;n||(n=new RegExp("(\\.?"+u.type.replace(".","\\.").replace("lparen",".paren").replace(/\b(?:start|begin)\b/,"(?:start|begin|end)")+")+"));var a=t.column-o.getCurrentTokenColumn();for(;;){var f=u.value,l=f.length;while(a=4352&&e<=4447||e>=4515&&e<=4519||e>=4602&&e<=4607||e>=9001&&e<=9002||e>=11904&&e<=11929||e>=11931&&e<=12019||e>=12032&&e<=12245||e>=12272&&e<=12283||e>=12288&&e<=12350||e>=12353&&e<=12438||e>=12441&&e<=12543||e>=12549&&e<=12589||e>=12593&&e<=12686||e>=12688&&e<=12730||e>=12736&&e<=12771||e>=12784&&e<=12830||e>=12832&&e<=12871||e>=12880&&e<=13054||e>=13056&&e<=19903||e>=19968&&e<=42124||e>=42128&&e<=42182||e>=43360&&e<=43388||e>=44032&&e<=55203||e>=55216&&e<=55238||e>=55243&&e<=55291||e>=63744&&e<=64255||e>=65040&&e<=65049||e>=65072&&e<=65106||e>=65108&&e<=65126||e>=65128&&e<=65131||e>=65281&&e<=65376||e>=65504&&e<=65510}r.implement(this,u),this.setDocument=function(e){this.doc&&this.doc.removeListener("change",this.$onChange),this.doc=e,e.on("change",this.$onChange),this.bgTokenizer&&this.bgTokenizer.setDocument(this.getDocument()),this.resetCaches()},this.getDocument=function(){return this.doc},this.$resetRowCache=function(e){if(!e){this.$docRowCache=[],this.$screenRowCache=[];return}var t=this.$docRowCache.length,n=this.$getRowCacheIndex(this.$docRowCache,e)+1;t>n&&(this.$docRowCache.splice(n,t),this.$screenRowCache.splice(n,t))},this.$getRowCacheIndex=function(e,t){var n=0,r=e.length-1;while(n<=r){var i=n+r>>1,s=e[i];if(t>s)n=i+1;else{if(!(t=t)break}return r=n[s],r?(r.index=s,r.start=i-r.value.length,r):null},this.setUndoManager=function(e){this.$undoManager=e,this.$informUndoManager&&this.$informUndoManager.cancel();if(e){var t=this;e.addSession(this),this.$syncInformUndoManager=function(){t.$informUndoManager.cancel(),t.mergeUndoDeltas=!1},this.$informUndoManager=i.delayedCall(this.$syncInformUndoManager)}else this.$syncInformUndoManager=function(){}},this.markUndoGroup=function(){this.$syncInformUndoManager&&this.$syncInformUndoManager()},this.$defaultUndoManager={undo:function(){},redo:function(){},reset:function(){},add:function(){},addSelection:function(){},startNewGroup:function(){},addSession:function(){}},this.getUndoManager=function(){return this.$undoManager||this.$defaultUndoManager},this.getTabString=function(){return this.getUseSoftTabs()?i.stringRepeat(" ",this.getTabSize()):" "},this.setUseSoftTabs=function(e){this.setOption("useSoftTabs",e)},this.getUseSoftTabs=function(){return this.$useSoftTabs&&!this.$mode.$indentWithTabs},this.setTabSize=function(e){this.setOption("tabSize",e)},this.getTabSize=function(){return this.$tabSize},this.isTabStop=function(e){return this.$useSoftTabs&&e.column%this.$tabSize===0},this.setNavigateWithinSoftTabs=function(e){this.setOption("navigateWithinSoftTabs",e)},this.getNavigateWithinSoftTabs=function(){return this.$navigateWithinSoftTabs},this.$overwrite=!1,this.setOverwrite=function(e){this.setOption("overwrite",e)},this.getOverwrite=function(){return this.$overwrite},this.toggleOverwrite=function(){this.setOverwrite(!this.$overwrite)},this.addGutterDecoration=function(e,t){this.$decorations[e]||(this.$decorations[e]=""),this.$decorations[e]+=" "+t,this._signal("changeBreakpoint",{})},this.removeGutterDecoration=function(e,t){this.$decorations[e]=(this.$decorations[e]||"").replace(" "+t,""),this._signal("changeBreakpoint",{})},this.getBreakpoints=function(){return this.$breakpoints},this.setBreakpoints=function(e){this.$breakpoints=[];for(var t=0;t0&&(r=!!n.charAt(t-1).match(this.tokenRe)),r||(r=!!n.charAt(t).match(this.tokenRe));if(r)var i=this.tokenRe;else if(/^\s+$/.test(n.slice(t-1,t+1)))var i=/\s/;else var i=this.nonTokenRe;var s=t;if(s>0){do s--;while(s>=0&&n.charAt(s).match(i));s++}var o=t;while(oe&&(e=t.screenWidth)}),this.lineWidgetWidth=e},this.$computeWidth=function(e){if(this.$modified||e){this.$modified=!1;if(this.$useWrapMode)return this.screenWidth=this.$wrapLimit;var t=this.doc.getAllLines(),n=this.$rowLengthCache,r=0,i=0,s=this.$foldData[i],o=s?s.start.row:Infinity,u=t.length;for(var a=0;ao){a=s.end.row+1;if(a>=u)break;s=this.$foldData[i++],o=s?s.start.row:Infinity}n[a]==null&&(n[a]=this.$getStringScreenWidth(t[a])[0]),n[a]>r&&(r=n[a])}this.screenWidth=r}},this.getLine=function(e){return this.doc.getLine(e)},this.getLines=function(e,t){return this.doc.getLines(e,t)},this.getLength=function(){return this.doc.getLength()},this.getTextRange=function(e){return this.doc.getTextRange(e||this.selection.getRange())},this.insert=function(e,t){return this.doc.insert(e,t)},this.remove=function(e){return this.doc.remove(e)},this.removeFullLines=function(e,t){return this.doc.removeFullLines(e,t)},this.undoChanges=function(e,t){if(!e.length)return;this.$fromUndo=!0;for(var n=e.length-1;n!=-1;n--){var r=e[n];r.action=="insert"||r.action=="remove"?this.doc.revertDelta(r):r.folds&&this.addFolds(r.folds)}!t&&this.$undoSelect&&(e.selectionBefore?this.selection.fromJSON(e.selectionBefore):this.selection.setRange(this.$getUndoSelection(e,!0))),this.$fromUndo=!1},this.redoChanges=function(e,t){if(!e.length)return;this.$fromUndo=!0;for(var n=0;ne.end.column&&(s.start.column+=u),s.end.row==e.end.row&&s.end.column>e.end.column&&(s.end.column+=u)),o&&s.start.row>=e.end.row&&(s.start.row+=o,s.end.row+=o)}s.end=this.insert(s.start,r);if(i.length){var a=e.start,f=s.start,o=f.row-a.row,u=f.column-a.column;this.addFolds(i.map(function(e){return e=e.clone(),e.start.row==a.row&&(e.start.column+=u),e.end.row==a.row&&(e.end.column+=u),e.start.row+=o,e.end.row+=o,e}))}return s},this.indentRows=function(e,t,n){n=n.replace(/\t/g,this.getTabString());for(var r=e;r<=t;r++)this.doc.insertInLine({row:r,column:0},n)},this.outdentRows=function(e){var t=e.collapseRows(),n=new l(0,0,0,0),r=this.getTabSize();for(var i=t.start.row;i<=t.end.row;++i){var s=this.getLine(i);n.start.row=i,n.end.row=i;for(var o=0;o0){var r=this.getRowFoldEnd(t+n);if(r>this.doc.getLength()-1)return 0;var i=r-t}else{e=this.$clipRowToDocument(e),t=this.$clipRowToDocument(t);var i=t-e+1}var s=new l(e,0,t,Number.MAX_VALUE),o=this.getFoldsInRange(s).map(function(e){return e=e.clone(),e.start.row+=i,e.end.row+=i,e}),u=n==0?this.doc.getLines(e,t):this.doc.removeFullLines(e,t);return this.doc.insertFullLines(e+i,u),o.length&&this.addFolds(o),i},this.moveLinesUp=function(e,t){return this.$moveLines(e,t,-1)},this.moveLinesDown=function(e,t){return this.$moveLines(e,t,1)},this.duplicateLines=function(e,t){return this.$moveLines(e,t,0)},this.$clipRowToDocument=function(e){return Math.max(0,Math.min(e,this.doc.getLength()-1))},this.$clipColumnToRow=function(e,t){return t<0?0:Math.min(this.doc.getLine(e).length,t)},this.$clipPositionToDocument=function(e,t){t=Math.max(0,t);if(e<0)e=0,t=0;else{var n=this.doc.getLength();e>=n?(e=n-1,t=this.doc.getLine(n-1).length):t=Math.min(this.doc.getLine(e).length,t)}return{row:e,column:t}},this.$clipRangeToDocument=function(e){e.start.row<0?(e.start.row=0,e.start.column=0):e.start.column=this.$clipColumnToRow(e.start.row,e.start.column);var t=this.doc.getLength()-1;return e.end.row>t?(e.end.row=t,e.end.column=this.doc.getLine(t).length):e.end.column=this.$clipColumnToRow(e.end.row,e.end.column),e},this.$wrapLimit=80,this.$useWrapMode=!1,this.$wrapLimitRange={min:null,max:null},this.setUseWrapMode=function(e){if(e!=this.$useWrapMode){this.$useWrapMode=e,this.$modified=!0,this.$resetRowCache(0);if(e){var t=this.getLength();this.$wrapData=Array(t),this.$updateWrapData(0,t-1)}this._signal("changeWrapMode")}},this.getUseWrapMode=function(){return this.$useWrapMode},this.setWrapLimitRange=function(e,t){if(this.$wrapLimitRange.min!==e||this.$wrapLimitRange.max!==t)this.$wrapLimitRange={min:e,max:t},this.$modified=!0,this.$bidiHandler.markAsDirty(),this.$useWrapMode&&this._signal("changeWrapMode")},this.adjustWrapLimit=function(e,t){var n=this.$wrapLimitRange;n.max<0&&(n={min:t,max:t});var r=this.$constrainWrapLimit(e,n.min,n.max);return r!=this.$wrapLimit&&r>1?(this.$wrapLimit=r,this.$modified=!0,this.$useWrapMode&&(this.$updateWrapData(0,this.getLength()-1),this.$resetRowCache(0),this._signal("changeWrapLimit")),!0):!1},this.$constrainWrapLimit=function(e,t,n){return t&&(e=Math.max(t,e)),n&&(e=Math.min(n,e)),e},this.getWrapLimit=function(){return this.$wrapLimit},this.setWrapLimit=function(e){this.setWrapLimitRange(e,e)},this.getWrapLimitRange=function(){return{min:this.$wrapLimitRange.min,max:this.$wrapLimitRange.max}},this.$updateInternalDataOnChange=function(e){var t=this.$useWrapMode,n=e.action,r=e.start,i=e.end,s=r.row,o=i.row,u=o-s,a=null;this.$updating=!0;if(u!=0)if(n==="remove"){this[t?"$wrapData":"$rowLengthCache"].splice(s,u);var f=this.$foldData;a=this.getFoldsInRange(e),this.removeFolds(a);var l=this.getFoldLine(i.row),c=0;if(l){l.addRemoveChars(i.row,i.column,r.column-i.column),l.shiftRow(-u);var h=this.getFoldLine(s);h&&h!==l&&(h.merge(l),l=h),c=f.indexOf(l)+1}for(c;c=i.row&&l.shiftRow(-u)}o=s}else{var p=Array(u);p.unshift(s,0);var d=t?this.$wrapData:this.$rowLengthCache;d.splice.apply(d,p);var f=this.$foldData,l=this.getFoldLine(s),c=0;if(l){var v=l.range.compareInside(r.row,r.column);v==0?(l=l.split(r.row,r.column),l&&(l.shiftRow(u),l.addRemoveChars(o,0,i.column-r.column))):v==-1&&(l.addRemoveChars(s,0,i.column-r.column),l.shiftRow(u)),c=f.indexOf(l)+1}for(c;c=s&&l.shiftRow(u)}}else{u=Math.abs(e.start.column-e.end.column),n==="remove"&&(a=this.getFoldsInRange(e),this.removeFolds(a),u=-u);var l=this.getFoldLine(s);l&&l.addRemoveChars(s,r.column,u)}return t&&this.$wrapData.length!=this.doc.getLength()&&console.error("doc.getLength() and $wrapData.length have to be the same!"),this.$updating=!1,t?this.$updateWrapData(s,o):this.$updateRowLengthCache(s,o),a},this.$updateRowLengthCache=function(e,t,n){this.$rowLengthCache[e]=null,this.$rowLengthCache[t]=null},this.$updateWrapData=function(e,t){var r=this.doc.getAllLines(),i=this.getTabSize(),o=this.$wrapData,u=this.$wrapLimit,a,f,l=e;t=Math.min(t,r.length-1);while(l<=t)f=this.getFoldLine(l,f),f?(a=[],f.walk(function(e,t,i,o){var u;if(e!=null){u=this.$getDisplayTokens(e,a.length),u[0]=n;for(var f=1;fr-b){var w=f+r-b;if(e[w-1]>=c&&e[w]>=c){y(w);continue}if(e[w]==n||e[w]==s){for(w;w!=f-1;w--)if(e[w]==n)break;if(w>f){y(w);continue}w=f+r;for(w;w>2)),f-1);while(w>E&&e[w]E&&e[w]E&&e[w]==a)w--}else while(w>E&&e[w]E){y(++w);continue}w=f+r,e[w]==t&&w--,y(w-b)}return o},this.$getDisplayTokens=function(n,r){var i=[],s;r=r||0;for(var o=0;o39&&u<48||u>57&&u<64?i.push(a):u>=4352&&m(u)?i.push(e,t):i.push(e)}return i},this.$getStringScreenWidth=function(e,t,n){if(t==0)return[0,0];t==null&&(t=Infinity),n=n||0;var r,i;for(i=0;i=4352&&m(r)?n+=2:n+=1;if(n>t)break}return[n,i]},this.lineWidgets=null,this.getRowLength=function(e){if(this.lineWidgets)var t=this.lineWidgets[e]&&this.lineWidgets[e].rowCount||0;else t=0;return!this.$useWrapMode||!this.$wrapData[e]?1+t:this.$wrapData[e].length+1+t},this.getRowLineCount=function(e){return!this.$useWrapMode||!this.$wrapData[e]?1:this.$wrapData[e].length+1},this.getRowWrapIndent=function(e){if(this.$useWrapMode){var t=this.screenToDocumentPosition(e,Number.MAX_VALUE),n=this.$wrapData[t.row];return n.length&&n[0]=0)var u=f[l],i=this.$docRowCache[l],h=e>f[c-1];else var h=!c;var p=this.getLength()-1,d=this.getNextFoldLine(i),v=d?d.start.row:Infinity;while(u<=e){a=this.getRowLength(i);if(u+a>e||i>=p)break;u+=a,i++,i>v&&(i=d.end.row+1,d=this.getNextFoldLine(i,d),v=d?d.start.row:Infinity),h&&(this.$docRowCache.push(i),this.$screenRowCache.push(u))}if(d&&d.start.row<=i)r=this.getFoldDisplayLine(d),i=d.start.row;else{if(u+a<=e||i>p)return{row:p,column:this.getLine(p).length};r=this.getLine(i),d=null}var m=0,g=Math.floor(e-u);if(this.$useWrapMode){var y=this.$wrapData[i];y&&(o=y[g],g>0&&y.length&&(m=y.indent,s=y[g-1]||y[y.length-1],r=r.substring(s)))}return n!==undefined&&this.$bidiHandler.isBidiRow(u+g,i,g)&&(t=this.$bidiHandler.offsetToCol(n)),s+=this.$getStringScreenWidth(r,t-m)[1],this.$useWrapMode&&s>=o&&(s=o-1),d?d.idxToPosition(s):{row:i,column:s}},this.documentToScreenPosition=function(e,t){if(typeof t=="undefined")var n=this.$clipPositionToDocument(e.row,e.column);else n=this.$clipPositionToDocument(e,t);e=n.row,t=n.column;var r=0,i=null,s=null;s=this.getFoldAt(e,t,1),s&&(e=s.start.row,t=s.start.column);var o,u=0,a=this.$docRowCache,f=this.$getRowCacheIndex(a,e),l=a.length;if(l&&f>=0)var u=a[f],r=this.$screenRowCache[f],c=e>a[l-1];else var c=!l;var h=this.getNextFoldLine(u),p=h?h.start.row:Infinity;while(u=p){o=h.end.row+1;if(o>e)break;h=this.getNextFoldLine(o,h),p=h?h.start.row:Infinity}else o=u+1;r+=this.getRowLength(u),u=o,c&&(this.$docRowCache.push(u),this.$screenRowCache.push(r))}var d="";h&&u>=p?(d=this.getFoldDisplayLine(h,e,t),i=h.start.row):(d=this.getLine(e).substring(0,t),i=e);var v=0;if(this.$useWrapMode){var m=this.$wrapData[i];if(m){var g=0;while(d.length>=m[g])r++,g++;d=d.substring(m[g-1]||0,d.length),v=g>0?m.indent:0}}return{row:r,column:v+this.$getStringScreenWidth(d)[0]}},this.documentToScreenColumn=function(e,t){return this.documentToScreenPosition(e,t).column},this.documentToScreenRow=function(e,t){return this.documentToScreenPosition(e,t).row},this.getScreenLength=function(){var e=0,t=null;if(!this.$useWrapMode){e=this.getLength();var n=this.$foldData;for(var r=0;ro&&(s=t.end.row+1,t=this.$foldData[r++],o=t?t.start.row:Infinity)}}return this.lineWidgets&&(e+=this.$getWidgetScreenLength()),e},this.$setFontMetrics=function(e){if(!this.$enableVarChar)return;this.$getStringScreenWidth=function(t,n,r){if(n===0)return[0,0];n||(n=Infinity),r=r||0;var i,s;for(s=0;sn)break}return[r,s]}},this.destroy=function(){this.bgTokenizer&&(this.bgTokenizer.setDocument(null),this.bgTokenizer=null),this.$stopWorker()},this.isFullWidth=m}.call(d.prototype),e("./edit_session/folding").Folding.call(d.prototype),e("./edit_session/bracket_match").BracketMatch.call(d.prototype),o.defineOptions(d.prototype,"session",{wrap:{set:function(e){!e||e=="off"?e=!1:e=="free"?e=!0:e=="printMargin"?e=-1:typeof e=="string"&&(e=parseInt(e,10)||!1);if(this.$wrap==e)return;this.$wrap=e;if(!e)this.setUseWrapMode(!1);else{var t=typeof e=="number"?e:null;this.setWrapLimitRange(t,t),this.setUseWrapMode(!0)}},get:function(){return this.getUseWrapMode()?this.$wrap==-1?"printMargin":this.getWrapLimitRange().min?this.$wrap:"free":"off"},handlesSet:!0},wrapMethod:{set:function(e){e=e=="auto"?this.$mode.type!="text":e!="text",e!=this.$wrapAsCode&&(this.$wrapAsCode=e,this.$useWrapMode&&(this.$useWrapMode=!1,this.setUseWrapMode(!0)))},initialValue:"auto"},indentedSoftWrap:{set:function(){this.$useWrapMode&&(this.$useWrapMode=!1,this.setUseWrapMode(!0))},initialValue:!0},firstLineNumber:{set:function(){this._signal("changeBreakpoint")},initialValue:1},useWorker:{set:function(e){this.$useWorker=e,this.$stopWorker(),e&&this.$startWorker()},initialValue:!0},useSoftTabs:{initialValue:!0},tabSize:{set:function(e){e=parseInt(e),e>0&&this.$tabSize!==e&&(this.$modified=!0,this.$rowLengthCache=[],this.$tabSize=e,this._signal("changeTabSize"))},initialValue:4,handlesSet:!0},navigateWithinSoftTabs:{initialValue:!1},foldStyle:{set:function(e){this.setFoldStyle(e)},handlesSet:!0},overwrite:{set:function(e){this._signal("changeOverwrite")},initialValue:!1},newLineMode:{set:function(e){this.doc.setNewLineMode(e)},get:function(){return this.doc.getNewLineMode()},handlesSet:!0},mode:{set:function(e){this.setMode(e)},get:function(){return this.$modeId},handlesSet:!0}}),t.EditSession=d}),ace.define("ace/search",["require","exports","module","ace/lib/lang","ace/lib/oop","ace/range"],function(e,t,n){"use strict";function u(e,t){function n(e){return/\w/.test(e)||t.regExp?"\\b":""}return n(e[0])+e+n(e[e.length-1])}var r=e("./lib/lang"),i=e("./lib/oop"),s=e("./range").Range,o=function(){this.$options={}};(function(){this.set=function(e){return i.mixin(this.$options,e),this},this.getOptions=function(){return r.copyObject(this.$options)},this.setOptions=function(e){this.$options=e},this.find=function(e){var t=this.$options,n=this.$matchIterator(e,t);if(!n)return!1;var r=null;return n.forEach(function(e,n,i,o){return r=new s(e,n,i,o),n==o&&t.start&&t.start.start&&t.skipCurrent!=0&&r.isEqual(t.start)?(r=null,!1):!0}),r},this.findAll=function(e){var t=this.$options;if(!t.needle)return[];this.$assembleRegExp(t);var n=t.range,i=n?e.getLines(n.start.row,n.end.row):e.doc.getAllLines(),o=[],u=t.re;if(t.$isMultiLine){var a=u.length,f=i.length-a,l;e:for(var c=u.offset||0;c<=f;c++){for(var h=0;hv)continue;o.push(l=new s(c,v,c+a-1,m)),a>2&&(c=c+a-2)}}else for(var g=0;gE&&o[h].end.row==n.end.row)h--;o=o.slice(g,h+1);for(g=0,h=o.length;g=u;n--)if(c(n,Number.MAX_VALUE,e))return;if(t.wrap==0)return;for(n=a,u=o.row;n>=u;n--)if(c(n,Number.MAX_VALUE,e))return};else var f=function(e){var n=o.row;if(c(n,o.column,e))return;for(n+=1;n<=a;n++)if(c(n,0,e))return;if(t.wrap==0)return;for(n=u,a=o.row;n<=a;n++)if(c(n,0,e))return};if(t.$isMultiLine)var l=n.length,c=function(t,i,s){var o=r?t-l+1:t;if(o<0)return;var u=e.getLine(o),a=u.search(n[0]);if(!r&&ai)return;if(s(o,a,o+l-1,c))return!0};else if(r)var c=function(t,r,i){var s=e.getLine(t),o=[],u,a=0;n.lastIndex=0;while(u=n.exec(s)){var f=u[0].length;a=u.index;if(!f){if(a>=s.length)break;n.lastIndex=a+=1}if(u.index+f>r)break;o.push(u.index,f)}for(var l=o.length-1;l>=0;l-=2){var c=o[l-1],f=o[l];if(i(t,c,t,c+f))return!0}};else var c=function(t,r,i){var s=e.getLine(t),o,u;n.lastIndex=r;while(u=n.exec(s)){var a=u[0].length;o=u.index;if(i(t,o,t,o+a))return!0;if(!a){n.lastIndex=o+=1;if(o>=s.length)return!1}}};return{forEach:f}}}).call(o.prototype),t.Search=o}),ace.define("ace/keyboard/hash_handler",["require","exports","module","ace/lib/keys","ace/lib/useragent"],function(e,t,n){"use strict";function o(e,t){this.platform=t||(i.isMac?"mac":"win"),this.commands={},this.commandKeyBinding={},this.addCommands(e),this.$singleCommand=!0}function u(e,t){o.call(this,e,t),this.$singleCommand=!1}var r=e("../lib/keys"),i=e("../lib/useragent"),s=r.KEY_MODS;u.prototype=o.prototype,function(){function e(e){return typeof e=="object"&&e.bindKey&&e.bindKey.position||(e.isDefault?-100:0)}this.addCommand=function(e){this.commands[e.name]&&this.removeCommand(e),this.commands[e.name]=e,e.bindKey&&this._buildKeyHash(e)},this.removeCommand=function(e,t){var n=e&&(typeof e=="string"?e:e.name);e=this.commands[n],t||delete this.commands[n];var r=this.commandKeyBinding;for(var i in r){var s=r[i];if(s==e)delete r[i];else if(Array.isArray(s)){var o=s.indexOf(e);o!=-1&&(s.splice(o,1),s.length==1&&(r[i]=s[0]))}}},this.bindKey=function(e,t,n){typeof e=="object"&&e&&(n==undefined&&(n=e.position),e=e[this.platform]);if(!e)return;if(typeof t=="function")return this.addCommand({exec:t,bindKey:e,name:t.name||e});e.split("|").forEach(function(e){var r="";if(e.indexOf(" ")!=-1){var i=e.split(/\s+/);e=i.pop(),i.forEach(function(e){var t=this.parseKeys(e),n=s[t.hashId]+t.key;r+=(r?" ":"")+n,this._addCommandToBinding(r,"chainKeys")},this),r+=" "}var o=this.parseKeys(e),u=s[o.hashId]+o.key;this._addCommandToBinding(r+u,t,n)},this)},this._addCommandToBinding=function(t,n,r){var i=this.commandKeyBinding,s;if(!n)delete i[t];else if(!i[t]||this.$singleCommand)i[t]=n;else{Array.isArray(i[t])?(s=i[t].indexOf(n))!=-1&&i[t].splice(s,1):i[t]=[i[t]],typeof r!="number"&&(r=e(n));var o=i[t];for(s=0;sr)break}o.splice(s,0,n)}},this.addCommands=function(e){e&&Object.keys(e).forEach(function(t){var n=e[t];if(!n)return;if(typeof n=="string")return this.bindKey(n,t);typeof n=="function"&&(n={exec:n});if(typeof n!="object")return;n.name||(n.name=t),this.addCommand(n)},this)},this.removeCommands=function(e){Object.keys(e).forEach(function(t){this.removeCommand(e[t])},this)},this.bindKeys=function(e){Object.keys(e).forEach(function(t){this.bindKey(t,e[t])},this)},this._buildKeyHash=function(e){this.bindKey(e.bindKey,e)},this.parseKeys=function(e){var t=e.toLowerCase().split(/[\-\+]([\-\+])?/).filter(function(e){return e}),n=t.pop(),i=r[n];if(r.FUNCTION_KEYS[i])n=r.FUNCTION_KEYS[i].toLowerCase();else{if(!t.length)return{key:n,hashId:-1};if(t.length==1&&t[0]=="shift")return{key:n.toUpperCase(),hashId:-1}}var s=0;for(var o=t.length;o--;){var u=r.KEY_MODS[t[o]];if(u==null)return typeof console!="undefined"&&console.error("invalid modifier "+t[o]+" in "+e),!1;s|=u}return{key:n,hashId:s}},this.findKeyCommand=function(t,n){var r=s[t]+n;return this.commandKeyBinding[r]},this.handleKeyboard=function(e,t,n,r){if(r<0)return;var i=s[t]+n,o=this.commandKeyBinding[i];e.$keyChain&&(e.$keyChain+=" "+i,o=this.commandKeyBinding[e.$keyChain]||o);if(o)if(o=="chainKeys"||o[o.length-1]=="chainKeys")return e.$keyChain=e.$keyChain||i,{command:"null"};if(e.$keyChain)if(!!t&&t!=4||n.length!=1){if(t==-1||r>0)e.$keyChain=""}else e.$keyChain=e.$keyChain.slice(0,-i.length-1);return{command:o}},this.getStatusText=function(e,t){return t.$keyChain||""}}.call(o.prototype),t.HashHandler=o,t.MultiHashHandler=u}),ace.define("ace/commands/command_manager",["require","exports","module","ace/lib/oop","ace/keyboard/hash_handler","ace/lib/event_emitter"],function(e,t,n){"use strict";var r=e("../lib/oop"),i=e("../keyboard/hash_handler").MultiHashHandler,s=e("../lib/event_emitter").EventEmitter,o=function(e,t){i.call(this,t,e),this.byName=this.commands,this.setDefaultHandler("exec",function(e){return e.command.exec(e.editor,e.args||{})})};r.inherits(o,i),function(){r.implement(this,s),this.exec=function(e,t,n){if(Array.isArray(e)){for(var r=e.length;r--;)if(this.exec(e[r],t,n))return!0;return!1}typeof e=="string"&&(e=this.commands[e]);if(!e)return!1;if(t&&t.$readOnly&&!e.readOnly)return!1;if(this.$checkCommandState!=0&&e.isAvailable&&!e.isAvailable(t))return!1;var i={editor:t,command:e,args:n};return i.returnValue=this._emit("exec",i),this._signal("afterExec",i),i.returnValue===!1?!1:!0},this.toggleRecording=function(e){if(this.$inReplay)return;return e&&e._emit("changeStatus"),this.recording?(this.macro.pop(),this.removeEventListener("exec",this.$addCommandToMacro),this.macro.length||(this.macro=this.oldMacro),this.recording=!1):(this.$addCommandToMacro||(this.$addCommandToMacro=function(e){this.macro.push([e.command,e.args])}.bind(this)),this.oldMacro=this.macro,this.macro=[],this.on("exec",this.$addCommandToMacro),this.recording=!0)},this.replay=function(e){if(this.$inReplay||!this.macro)return;if(this.recording)return this.toggleRecording(e);try{this.$inReplay=!0,this.macro.forEach(function(t){typeof t=="string"?this.exec(t,e):this.exec(t[0],e,t[1])},this)}finally{this.$inReplay=!1}},this.trimMacro=function(e){return e.map(function(e){return typeof e[0]!="string"&&(e[0]=e[0].name),e[1]||(e=e[0]),e})}}.call(o.prototype),t.CommandManager=o}),ace.define("ace/commands/default_commands",["require","exports","module","ace/lib/lang","ace/config","ace/range"],function(e,t,n){"use strict";function o(e,t){return{win:e,mac:t}}var r=e("../lib/lang"),i=e("../config"),s=e("../range").Range;t.commands=[{name:"showSettingsMenu",bindKey:o("Ctrl-,","Command-,"),exec:function(e){i.loadModule("ace/ext/settings_menu",function(t){t.init(e),e.showSettingsMenu()})},readOnly:!0},{name:"goToNextError",bindKey:o("Alt-E","F4"),exec:function(e){i.loadModule("./ext/error_marker",function(t){t.showErrorMarker(e,1)})},scrollIntoView:"animate",readOnly:!0},{name:"goToPreviousError",bindKey:o("Alt-Shift-E","Shift-F4"),exec:function(e){i.loadModule("./ext/error_marker",function(t){t.showErrorMarker(e,-1)})},scrollIntoView:"animate",readOnly:!0},{name:"selectall",description:"Select all",bindKey:o("Ctrl-A","Command-A"),exec:function(e){e.selectAll()},readOnly:!0},{name:"centerselection",description:"Center selection",bindKey:o(null,"Ctrl-L"),exec:function(e){e.centerSelection()},readOnly:!0},{name:"gotoline",description:"Go to line...",bindKey:o("Ctrl-L","Command-L"),exec:function(e,t){typeof t=="number"&&!isNaN(t)&&e.gotoLine(t),e.prompt({$type:"gotoLine"})},readOnly:!0},{name:"fold",bindKey:o("Alt-L|Ctrl-F1","Command-Alt-L|Command-F1"),exec:function(e){e.session.toggleFold(!1)},multiSelectAction:"forEach",scrollIntoView:"center",readOnly:!0},{name:"unfold",bindKey:o("Alt-Shift-L|Ctrl-Shift-F1","Command-Alt-Shift-L|Command-Shift-F1"),exec:function(e){e.session.toggleFold(!0)},multiSelectAction:"forEach",scrollIntoView:"center",readOnly:!0},{name:"toggleFoldWidget",bindKey:o("F2","F2"),exec:function(e){e.session.toggleFoldWidget()},multiSelectAction:"forEach",scrollIntoView:"center",readOnly:!0},{name:"toggleParentFoldWidget",bindKey:o("Alt-F2","Alt-F2"),exec:function(e){e.session.toggleFoldWidget(!0)},multiSelectAction:"forEach",scrollIntoView:"center",readOnly:!0},{name:"foldall",description:"Fold all",bindKey:o(null,"Ctrl-Command-Option-0"),exec:function(e){e.session.foldAll()},scrollIntoView:"center",readOnly:!0},{name:"foldOther",description:"Fold other",bindKey:o("Alt-0","Command-Option-0"),exec:function(e){e.session.foldAll(),e.session.unfold(e.selection.getAllRanges())},scrollIntoView:"center",readOnly:!0},{name:"unfoldall",description:"Unfold all",bindKey:o("Alt-Shift-0","Command-Option-Shift-0"),exec:function(e){e.session.unfold()},scrollIntoView:"center",readOnly:!0},{name:"findnext",description:"Find next",bindKey:o("Ctrl-K","Command-G"),exec:function(e){e.findNext()},multiSelectAction:"forEach",scrollIntoView:"center",readOnly:!0},{name:"findprevious",description:"Find previous",bindKey:o("Ctrl-Shift-K","Command-Shift-G"),exec:function(e){e.findPrevious()},multiSelectAction:"forEach",scrollIntoView:"center",readOnly:!0},{name:"selectOrFindNext",description:"Select or find next",bindKey:o("Alt-K","Ctrl-G"),exec:function(e){e.selection.isEmpty()?e.selection.selectWord():e.findNext()},readOnly:!0},{name:"selectOrFindPrevious",description:"Select or find previous",bindKey:o("Alt-Shift-K","Ctrl-Shift-G"),exec:function(e){e.selection.isEmpty()?e.selection.selectWord():e.findPrevious()},readOnly:!0},{name:"find",description:"Find",bindKey:o("Ctrl-F","Command-F"),exec:function(e){i.loadModule("ace/ext/searchbox",function(t){t.Search(e)})},readOnly:!0},{name:"overwrite",description:"Overwrite",bindKey:"Insert",exec:function(e){e.toggleOverwrite()},readOnly:!0},{name:"selecttostart",description:"Select to start",bindKey:o("Ctrl-Shift-Home","Command-Shift-Home|Command-Shift-Up"),exec:function(e){e.getSelection().selectFileStart()},multiSelectAction:"forEach",readOnly:!0,scrollIntoView:"animate",aceCommandGroup:"fileJump"},{name:"gotostart",description:"Go to start",bindKey:o("Ctrl-Home","Command-Home|Command-Up"),exec:function(e){e.navigateFileStart()},multiSelectAction:"forEach",readOnly:!0,scrollIntoView:"animate",aceCommandGroup:"fileJump"},{name:"selectup",description:"Select up",bindKey:o("Shift-Up","Shift-Up|Ctrl-Shift-P"),exec:function(e){e.getSelection().selectUp()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"golineup",description:"Go line up",bindKey:o("Up","Up|Ctrl-P"),exec:function(e,t){e.navigateUp(t.times)},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selecttoend",description:"Select to end",bindKey:o("Ctrl-Shift-End","Command-Shift-End|Command-Shift-Down"),exec:function(e){e.getSelection().selectFileEnd()},multiSelectAction:"forEach",readOnly:!0,scrollIntoView:"animate",aceCommandGroup:"fileJump"},{name:"gotoend",description:"Go to end",bindKey:o("Ctrl-End","Command-End|Command-Down"),exec:function(e){e.navigateFileEnd()},multiSelectAction:"forEach",readOnly:!0,scrollIntoView:"animate",aceCommandGroup:"fileJump"},{name:"selectdown",description:"Select down",bindKey:o("Shift-Down","Shift-Down|Ctrl-Shift-N"),exec:function(e){e.getSelection().selectDown()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"golinedown",description:"Go line down",bindKey:o("Down","Down|Ctrl-N"),exec:function(e,t){e.navigateDown(t.times)},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selectwordleft",description:"Select word left",bindKey:o("Ctrl-Shift-Left","Option-Shift-Left"),exec:function(e){e.getSelection().selectWordLeft()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"gotowordleft",description:"Go to word left",bindKey:o("Ctrl-Left","Option-Left"),exec:function(e){e.navigateWordLeft()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selecttolinestart",description:"Select to line start",bindKey:o("Alt-Shift-Left","Command-Shift-Left|Ctrl-Shift-A"),exec:function(e){e.getSelection().selectLineStart()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"gotolinestart",description:"Go to line start",bindKey:o("Alt-Left|Home","Command-Left|Home|Ctrl-A"),exec:function(e){e.navigateLineStart()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selectleft",description:"Select left",bindKey:o("Shift-Left","Shift-Left|Ctrl-Shift-B"),exec:function(e){e.getSelection().selectLeft()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"gotoleft",description:"Go to left",bindKey:o("Left","Left|Ctrl-B"),exec:function(e,t){e.navigateLeft(t.times)},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selectwordright",description:"Select word right",bindKey:o("Ctrl-Shift-Right","Option-Shift-Right"),exec:function(e){e.getSelection().selectWordRight()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"gotowordright",description:"Go to word right",bindKey:o("Ctrl-Right","Option-Right"),exec:function(e){e.navigateWordRight()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selecttolineend",description:"Select to line end",bindKey:o("Alt-Shift-Right","Command-Shift-Right|Shift-End|Ctrl-Shift-E"),exec:function(e){e.getSelection().selectLineEnd()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"gotolineend",description:"Go to line end",bindKey:o("Alt-Right|End","Command-Right|End|Ctrl-E"),exec:function(e){e.navigateLineEnd()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selectright",description:"Select right",bindKey:o("Shift-Right","Shift-Right"),exec:function(e){e.getSelection().selectRight()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"gotoright",description:"Go to right",bindKey:o("Right","Right|Ctrl-F"),exec:function(e,t){e.navigateRight(t.times)},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selectpagedown",description:"Select page down",bindKey:"Shift-PageDown",exec:function(e){e.selectPageDown()},readOnly:!0},{name:"pagedown",description:"Page down",bindKey:o(null,"Option-PageDown"),exec:function(e){e.scrollPageDown()},readOnly:!0},{name:"gotopagedown",description:"Go to page down",bindKey:o("PageDown","PageDown|Ctrl-V"),exec:function(e){e.gotoPageDown()},readOnly:!0},{name:"selectpageup",description:"Select page up",bindKey:"Shift-PageUp",exec:function(e){e.selectPageUp()},readOnly:!0},{name:"pageup",description:"Page up",bindKey:o(null,"Option-PageUp"),exec:function(e){e.scrollPageUp()},readOnly:!0},{name:"gotopageup",description:"Go to page up",bindKey:"PageUp",exec:function(e){e.gotoPageUp()},readOnly:!0},{name:"scrollup",description:"Scroll up",bindKey:o("Ctrl-Up",null),exec:function(e){e.renderer.scrollBy(0,-2*e.renderer.layerConfig.lineHeight)},readOnly:!0},{name:"scrolldown",description:"Scroll down",bindKey:o("Ctrl-Down",null),exec:function(e){e.renderer.scrollBy(0,2*e.renderer.layerConfig.lineHeight)},readOnly:!0},{name:"selectlinestart",description:"Select line start",bindKey:"Shift-Home",exec:function(e){e.getSelection().selectLineStart()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"selectlineend",description:"Select line end",bindKey:"Shift-End",exec:function(e){e.getSelection().selectLineEnd()},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"togglerecording",description:"Toggle recording",bindKey:o("Ctrl-Alt-E","Command-Option-E"),exec:function(e){e.commands.toggleRecording(e)},readOnly:!0},{name:"replaymacro",description:"Replay macro",bindKey:o("Ctrl-Shift-E","Command-Shift-E"),exec:function(e){e.commands.replay(e)},readOnly:!0},{name:"jumptomatching",description:"Jump to matching",bindKey:o("Ctrl-P","Ctrl-P"),exec:function(e){e.jumpToMatching()},multiSelectAction:"forEach",scrollIntoView:"animate",readOnly:!0},{name:"selecttomatching",description:"Select to matching",bindKey:o("Ctrl-Shift-P","Ctrl-Shift-P"),exec:function(e){e.jumpToMatching(!0)},multiSelectAction:"forEach",scrollIntoView:"animate",readOnly:!0},{name:"expandToMatching",description:"Expand to matching",bindKey:o("Ctrl-Shift-M","Ctrl-Shift-M"),exec:function(e){e.jumpToMatching(!0,!0)},multiSelectAction:"forEach",scrollIntoView:"animate",readOnly:!0},{name:"passKeysToBrowser",description:"Pass keys to browser",bindKey:o(null,null),exec:function(){},passEvent:!0,readOnly:!0},{name:"copy",description:"Copy",exec:function(e){},readOnly:!0},{name:"cut",description:"Cut",exec:function(e){var t=e.$copyWithEmptySelection&&e.selection.isEmpty(),n=t?e.selection.getLineRange():e.selection.getRange();e._emit("cut",n),n.isEmpty()||e.session.remove(n),e.clearSelection()},scrollIntoView:"cursor",multiSelectAction:"forEach"},{name:"paste",description:"Paste",exec:function(e,t){e.$handlePaste(t)},scrollIntoView:"cursor"},{name:"removeline",description:"Remove line",bindKey:o("Ctrl-D","Command-D"),exec:function(e){e.removeLines()},scrollIntoView:"cursor",multiSelectAction:"forEachLine"},{name:"duplicateSelection",description:"Duplicate selection",bindKey:o("Ctrl-Shift-D","Command-Shift-D"),exec:function(e){e.duplicateSelection()},scrollIntoView:"cursor",multiSelectAction:"forEach"},{name:"sortlines",description:"Sort lines",bindKey:o("Ctrl-Alt-S","Command-Alt-S"),exec:function(e){e.sortLines()},scrollIntoView:"selection",multiSelectAction:"forEachLine"},{name:"togglecomment",description:"Toggle comment",bindKey:o("Ctrl-/","Command-/"),exec:function(e){e.toggleCommentLines()},multiSelectAction:"forEachLine",scrollIntoView:"selectionPart"},{name:"toggleBlockComment",description:"Toggle block comment",bindKey:o("Ctrl-Shift-/","Command-Shift-/"),exec:function(e){e.toggleBlockComment()},multiSelectAction:"forEach",scrollIntoView:"selectionPart"},{name:"modifyNumberUp",description:"Modify number up",bindKey:o("Ctrl-Shift-Up","Alt-Shift-Up"),exec:function(e){e.modifyNumber(1)},scrollIntoView:"cursor",multiSelectAction:"forEach"},{name:"modifyNumberDown",description:"Modify number down",bindKey:o("Ctrl-Shift-Down","Alt-Shift-Down"),exec:function(e){e.modifyNumber(-1)},scrollIntoView:"cursor",multiSelectAction:"forEach"},{name:"replace",description:"Replace",bindKey:o("Ctrl-H","Command-Option-F"),exec:function(e){i.loadModule("ace/ext/searchbox",function(t){t.Search(e,!0)})}},{name:"undo",description:"Undo",bindKey:o("Ctrl-Z","Command-Z"),exec:function(e){e.undo()}},{name:"redo",description:"Redo",bindKey:o("Ctrl-Shift-Z|Ctrl-Y","Command-Shift-Z|Command-Y"),exec:function(e){e.redo()}},{name:"copylinesup",description:"Copy lines up",bindKey:o("Alt-Shift-Up","Command-Option-Up"),exec:function(e){e.copyLinesUp()},scrollIntoView:"cursor"},{name:"movelinesup",description:"Move lines up",bindKey:o("Alt-Up","Option-Up"),exec:function(e){e.moveLinesUp()},scrollIntoView:"cursor"},{name:"copylinesdown",description:"Copy lines down",bindKey:o("Alt-Shift-Down","Command-Option-Down"),exec:function(e){e.copyLinesDown()},scrollIntoView:"cursor"},{name:"movelinesdown",description:"Move lines down",bindKey:o("Alt-Down","Option-Down"),exec:function(e){e.moveLinesDown()},scrollIntoView:"cursor"},{name:"del",description:"Delete",bindKey:o("Delete","Delete|Ctrl-D|Shift-Delete"),exec:function(e){e.remove("right")},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"backspace",description:"Backspace",bindKey:o("Shift-Backspace|Backspace","Ctrl-Backspace|Shift-Backspace|Backspace|Ctrl-H"),exec:function(e){e.remove("left")},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"cut_or_delete",description:"Cut or delete",bindKey:o("Shift-Delete",null),exec:function(e){if(!e.selection.isEmpty())return!1;e.remove("left")},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"removetolinestart",description:"Remove to line start",bindKey:o("Alt-Backspace","Command-Backspace"),exec:function(e){e.removeToLineStart()},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"removetolineend",description:"Remove to line end",bindKey:o("Alt-Delete","Ctrl-K|Command-Delete"),exec:function(e){e.removeToLineEnd()},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"removetolinestarthard",description:"Remove to line start hard",bindKey:o("Ctrl-Shift-Backspace",null),exec:function(e){var t=e.selection.getRange();t.start.column=0,e.session.remove(t)},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"removetolineendhard",description:"Remove to line end hard",bindKey:o("Ctrl-Shift-Delete",null),exec:function(e){var t=e.selection.getRange();t.end.column=Number.MAX_VALUE,e.session.remove(t)},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"removewordleft",description:"Remove word left",bindKey:o("Ctrl-Backspace","Alt-Backspace|Ctrl-Alt-Backspace"),exec:function(e){e.removeWordLeft()},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"removewordright",description:"Remove word right",bindKey:o("Ctrl-Delete","Alt-Delete"),exec:function(e){e.removeWordRight()},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"outdent",description:"Outdent",bindKey:o("Shift-Tab","Shift-Tab"),exec:function(e){e.blockOutdent()},multiSelectAction:"forEach",scrollIntoView:"selectionPart"},{name:"indent",description:"Indent",bindKey:o("Tab","Tab"),exec:function(e){e.indent()},multiSelectAction:"forEach",scrollIntoView:"selectionPart"},{name:"blockoutdent",description:"Block outdent",bindKey:o("Ctrl-[","Ctrl-["),exec:function(e){e.blockOutdent()},multiSelectAction:"forEachLine",scrollIntoView:"selectionPart"},{name:"blockindent",description:"Block indent",bindKey:o("Ctrl-]","Ctrl-]"),exec:function(e){e.blockIndent()},multiSelectAction:"forEachLine",scrollIntoView:"selectionPart"},{name:"insertstring",description:"Insert string",exec:function(e,t){e.insert(t)},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"inserttext",description:"Insert text",exec:function(e,t){e.insert(r.stringRepeat(t.text||"",t.times||1))},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"splitline",description:"Split line",bindKey:o(null,"Ctrl-O"),exec:function(e){e.splitLine()},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"transposeletters",description:"Transpose letters",bindKey:o("Alt-Shift-X","Ctrl-T"),exec:function(e){e.transposeLetters()},multiSelectAction:function(e){e.transposeSelections(1)},scrollIntoView:"cursor"},{name:"touppercase",description:"To uppercase",bindKey:o("Ctrl-U","Ctrl-U"),exec:function(e){e.toUpperCase()},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"tolowercase",description:"To lowercase",bindKey:o("Ctrl-Shift-U","Ctrl-Shift-U"),exec:function(e){e.toLowerCase()},multiSelectAction:"forEach",scrollIntoView:"cursor"},{name:"expandtoline",description:"Expand to line",bindKey:o("Ctrl-Shift-L","Command-Shift-L"),exec:function(e){var t=e.selection.getRange();t.start.column=t.end.column=0,t.end.row++,e.selection.setRange(t,!1)},multiSelectAction:"forEach",scrollIntoView:"cursor",readOnly:!0},{name:"joinlines",description:"Join lines",bindKey:o(null,null),exec:function(e){var t=e.selection.isBackwards(),n=t?e.selection.getSelectionLead():e.selection.getSelectionAnchor(),i=t?e.selection.getSelectionAnchor():e.selection.getSelectionLead(),o=e.session.doc.getLine(n.row).length,u=e.session.doc.getTextRange(e.selection.getRange()),a=u.replace(/\n\s*/," ").length,f=e.session.doc.getLine(n.row);for(var l=n.row+1;l<=i.row+1;l++){var c=r.stringTrimLeft(r.stringTrimRight(e.session.doc.getLine(l)));c.length!==0&&(c=" "+c),f+=c}i.row+10?(e.selection.moveCursorTo(n.row,n.column),e.selection.selectTo(n.row,n.column+a)):(o=e.session.doc.getLine(n.row).length>o?o+1:o,e.selection.moveCursorTo(n.row,o))},multiSelectAction:"forEach",readOnly:!0},{name:"invertSelection",description:"Invert selection",bindKey:o(null,null),exec:function(e){var t=e.session.doc.getLength()-1,n=e.session.doc.getLine(t).length,r=e.selection.rangeList.ranges,i=[];r.length<1&&(r=[e.selection.getRange()]);for(var o=0;o=i.lastRow||r.end.row<=i.firstRow)&&this.renderer.scrollSelectionIntoView(this.selection.anchor,this.selection.lead);break;default:}n=="animate"&&this.renderer.animateScrolling(this.curOp.scrollTop)}var s=this.selection.toJSON();this.curOp.selectionAfter=s,this.$lastSel=this.selection.toJSON(),this.session.getUndoManager().addSelection(s),this.prevOp=this.curOp,this.curOp=null}},this.$mergeableCommands=["backspace","del","insertstring"],this.$historyTracker=function(e){if(!this.$mergeUndoDeltas)return;var t=this.prevOp,n=this.$mergeableCommands,r=t.command&&e.command.name==t.command.name;if(e.command.name=="insertstring"){var i=e.args;this.mergeNextCommand===undefined&&(this.mergeNextCommand=!0),r=r&&this.mergeNextCommand&&(!/\s/.test(i)||/\s/.test(t.args)),this.mergeNextCommand=!0}else r=r&&n.indexOf(e.command.name)!==-1;this.$mergeUndoDeltas!="always"&&Date.now()-this.sequenceStartTime>2e3&&(r=!1),r?this.session.mergeUndoDeltas=!0:n.indexOf(e.command.name)!==-1&&(this.sequenceStartTime=Date.now())},this.setKeyboardHandler=function(e,t){if(e&&typeof e=="string"&&e!="ace"){this.$keybindingId=e;var n=this;g.loadModule(["keybinding",e],function(r){n.$keybindingId==e&&n.keyBinding.setKeyboardHandler(r&&r.handler),t&&t()})}else this.$keybindingId=null,this.keyBinding.setKeyboardHandler(e),t&&t()},this.getKeyboardHandler=function(){return this.keyBinding.getKeyboardHandler()},this.setSession=function(e){if(this.session==e)return;this.curOp&&this.endOperation(),this.curOp={};var t=this.session;if(t){this.session.off("change",this.$onDocumentChange),this.session.off("changeMode",this.$onChangeMode),this.session.off("tokenizerUpdate",this.$onTokenizerUpdate),this.session.off("changeTabSize",this.$onChangeTabSize),this.session.off("changeWrapLimit",this.$onChangeWrapLimit),this.session.off("changeWrapMode",this.$onChangeWrapMode),this.session.off("changeFold",this.$onChangeFold),this.session.off("changeFrontMarker",this.$onChangeFrontMarker),this.session.off("changeBackMarker",this.$onChangeBackMarker),this.session.off("changeBreakpoint",this.$onChangeBreakpoint),this.session.off("changeAnnotation",this.$onChangeAnnotation),this.session.off("changeOverwrite",this.$onCursorChange),this.session.off("changeScrollTop",this.$onScrollTopChange),this.session.off("changeScrollLeft",this.$onScrollLeftChange);var n=this.session.getSelection();n.off("changeCursor",this.$onCursorChange),n.off("changeSelection",this.$onSelectionChange)}this.session=e,e?(this.$onDocumentChange=this.onDocumentChange.bind(this),e.on("change",this.$onDocumentChange),this.renderer.setSession(e),this.$onChangeMode=this.onChangeMode.bind(this),e.on("changeMode",this.$onChangeMode),this.$onTokenizerUpdate=this.onTokenizerUpdate.bind(this),e.on("tokenizerUpdate",this.$onTokenizerUpdate),this.$onChangeTabSize=this.renderer.onChangeTabSize.bind(this.renderer),e.on("changeTabSize",this.$onChangeTabSize),this.$onChangeWrapLimit=this.onChangeWrapLimit.bind(this),e.on("changeWrapLimit",this.$onChangeWrapLimit),this.$onChangeWrapMode=this.onChangeWrapMode.bind(this),e.on("changeWrapMode",this.$onChangeWrapMode),this.$onChangeFold=this.onChangeFold.bind(this),e.on("changeFold",this.$onChangeFold),this.$onChangeFrontMarker=this.onChangeFrontMarker.bind(this),this.session.on("changeFrontMarker",this.$onChangeFrontMarker),this.$onChangeBackMarker=this.onChangeBackMarker.bind(this),this.session.on("changeBackMarker",this.$onChangeBackMarker),this.$onChangeBreakpoint=this.onChangeBreakpoint.bind(this),this.session.on("changeBreakpoint",this.$onChangeBreakpoint),this.$onChangeAnnotation=this.onChangeAnnotation.bind(this),this.session.on("changeAnnotation",this.$onChangeAnnotation),this.$onCursorChange=this.onCursorChange.bind(this),this.session.on("changeOverwrite",this.$onCursorChange),this.$onScrollTopChange=this.onScrollTopChange.bind(this),this.session.on("changeScrollTop",this.$onScrollTopChange),this.$onScrollLeftChange=this.onScrollLeftChange.bind(this),this.session.on("changeScrollLeft",this.$onScrollLeftChange),this.selection=e.getSelection(),this.selection.on("changeCursor",this.$onCursorChange),this.$onSelectionChange=this.onSelectionChange.bind(this),this.selection.on("changeSelection",this.$onSelectionChange),this.onChangeMode(),this.onCursorChange(),this.onScrollTopChange(),this.onScrollLeftChange(),this.onSelectionChange(),this.onChangeFrontMarker(),this.onChangeBackMarker(),this.onChangeBreakpoint(),this.onChangeAnnotation(),this.session.getUseWrapMode()&&this.renderer.adjustWrapLimit(),this.renderer.updateFull()):(this.selection=null,this.renderer.setSession(e)),this._signal("changeSession",{session:e,oldSession:t}),this.curOp=null,t&&t._signal("changeEditor",{oldEditor:this}),e&&e._signal("changeEditor",{editor:this}),e&&e.bgTokenizer&&e.bgTokenizer.scheduleStart()},this.getSession=function(){return this.session},this.setValue=function(e,t){return this.session.doc.setValue(e),t?t==1?this.navigateFileEnd():t==-1&&this.navigateFileStart():this.selectAll(),e},this.getValue=function(){return this.session.getValue()},this.getSelection=function(){return this.selection},this.resize=function(e){this.renderer.onResize(e)},this.setTheme=function(e,t){this.renderer.setTheme(e,t)},this.getTheme=function(){return this.renderer.getTheme()},this.setStyle=function(e){this.renderer.setStyle(e)},this.unsetStyle=function(e){this.renderer.unsetStyle(e)},this.getFontSize=function(){return this.getOption("fontSize")||i.computedStyle(this.container).fontSize},this.setFontSize=function(e){this.setOption("fontSize",e)},this.$highlightBrackets=function(){this.session.$bracketHighlight&&(this.session.removeMarker(this.session.$bracketHighlight),this.session.$bracketHighlight=null);if(this.$highlightPending)return;var e=this;this.$highlightPending=!0,setTimeout(function(){e.$highlightPending=!1;var t=e.session;if(!t||!t.bgTokenizer)return;var n=t.findMatchingBracket(e.getCursorPosition());if(n)var r=new p(n.row,n.column,n.row,n.column+1);else if(t.$mode.getMatching)var r=t.$mode.getMatching(e.session);r&&(t.$bracketHighlight=t.addMarker(r,"ace_bracket","text"))},50)},this.$highlightTags=function(){if(this.$highlightTagPending)return;var e=this;this.$highlightTagPending=!0,setTimeout(function(){e.$highlightTagPending=!1;var t=e.session;if(!t||!t.bgTokenizer)return;var n=e.getCursorPosition(),r=new y(e.session,n.row,n.column),i=r.getCurrentToken();if(!i||!/\b(?:tag-open|tag-name)/.test(i.type)){t.removeMarker(t.$tagHighlight),t.$tagHighlight=null;return}if(i.type.indexOf("tag-open")!=-1){i=r.stepForward();if(!i)return}var s=i.value,o=0,u=r.stepBackward();if(u.value=="<"){do u=i,i=r.stepForward(),i&&i.value===s&&i.type.indexOf("tag-name")!==-1&&(u.value==="<"?o++:u.value==="=0)}else{do i=u,u=r.stepBackward(),i&&i.value===s&&i.type.indexOf("tag-name")!==-1&&(u.value==="<"?o++:u.value==="1)&&(t=!1)}if(e.$highlightLineMarker&&!t)e.removeMarker(e.$highlightLineMarker.id),e.$highlightLineMarker=null;else if(!e.$highlightLineMarker&&t){var n=new p(t.row,t.column,t.row,Infinity);n.id=e.addMarker(n,"ace_active-line","screenLine"),e.$highlightLineMarker=n}else t&&(e.$highlightLineMarker.start.row=t.row,e.$highlightLineMarker.end.row=t.row,e.$highlightLineMarker.start.column=t.column,e._signal("changeBackMarker"))},this.onSelectionChange=function(e){var t=this.session;t.$selectionMarker&&t.removeMarker(t.$selectionMarker),t.$selectionMarker=null;if(!this.selection.isEmpty()){var n=this.selection.getRange(),r=this.getSelectionStyle();t.$selectionMarker=t.addMarker(n,"ace_selection",r)}else this.$updateHighlightActiveLine();var i=this.$highlightSelectedWord&&this.$getSelectionHighLightRegexp();this.session.highlight(i),this._signal("changeSelection")},this.$getSelectionHighLightRegexp=function(){var e=this.session,t=this.getSelectionRange();if(t.isEmpty()||t.isMultiLine())return;var n=t.start.column,r=t.end.column,i=e.getLine(t.start.row),s=i.substring(n,r);if(s.length>5e3||!/[\w\d]/.test(s))return;var o=this.$search.$assembleRegExp({wholeWord:!0,caseSensitive:!0,needle:s}),u=i.substring(n-1,r+1);if(!o.test(u))return;return o},this.onChangeFrontMarker=function(){this.renderer.updateFrontMarkers()},this.onChangeBackMarker=function(){this.renderer.updateBackMarkers()},this.onChangeBreakpoint=function(){this.renderer.updateBreakpoints()},this.onChangeAnnotation=function(){this.renderer.setAnnotations(this.session.getAnnotations())},this.onChangeMode=function(e){this.renderer.updateText(),this._emit("changeMode",e)},this.onChangeWrapLimit=function(){this.renderer.updateFull()},this.onChangeWrapMode=function(){this.renderer.onResize(!0)},this.onChangeFold=function(){this.$updateHighlightActiveLine(),this.renderer.updateFull()},this.getSelectedText=function(){return this.session.getTextRange(this.getSelectionRange())},this.getCopyText=function(){var e=this.getSelectedText(),t=this.session.doc.getNewLineCharacter(),n=!1;if(!e&&this.$copyWithEmptySelection){n=!0;var r=this.selection.getAllRanges();for(var i=0;is.length||i.length<2||!i[1])return this.commands.exec("insertstring",this,t);for(var o=s.length;o--;){var u=s[o];u.isEmpty()||r.remove(u),r.insert(u.start,i[o])}}},this.execCommand=function(e,t){return this.commands.exec(e,this,t)},this.insert=function(e,t){var n=this.session,r=n.getMode(),i=this.getCursorPosition();if(this.getBehavioursEnabled()&&!t){var s=r.transformAction(n.getState(i.row),"insertion",this,n,e);s&&(e!==s.text&&(this.inVirtualSelectionMode||(this.session.mergeUndoDeltas=!1,this.mergeNextCommand=!1)),e=s.text)}e==" "&&(e=this.session.getTabString());if(!this.selection.isEmpty()){var o=this.getSelectionRange();i=this.session.remove(o),this.clearSelection()}else if(this.session.getOverwrite()&&e.indexOf("\n")==-1){var o=new p.fromPoints(i,i);o.end.column+=e.length,this.session.remove(o)}if(e=="\n"||e=="\r\n"){var u=n.getLine(i.row);if(i.column>u.search(/\S|$/)){var a=u.substr(i.column).search(/\S|$/);n.doc.removeInLine(i.row,i.column,i.column+a)}}this.clearSelection();var f=i.column,l=n.getState(i.row),u=n.getLine(i.row),c=r.checkOutdent(l,u,e),h=n.insert(i,e);s&&s.selection&&(s.selection.length==2?this.selection.setSelectionRange(new p(i.row,f+s.selection[0],i.row,f+s.selection[1])):this.selection.setSelectionRange(new p(i.row+s.selection[0],s.selection[1],i.row+s.selection[2],s.selection[3])));if(n.getDocument().isNewLine(e)){var d=r.getNextLineIndent(l,u.slice(0,i.column),n.getTabString());n.insert({row:i.row+1,column:0},d)}c&&r.autoOutdent(l,n,i.row)},this.onTextInput=function(e,t){if(!t)return this.keyBinding.onTextInput(e);this.startOperation({command:{name:"insertstring"}});var n=this.applyComposition.bind(this,e,t);this.selection.rangeCount?this.forEachSelection(n):n(),this.endOperation()},this.applyComposition=function(e,t){if(t.extendLeft||t.extendRight){var n=this.selection.getRange();n.start.column-=t.extendLeft,n.end.column+=t.extendRight,this.selection.setRange(n),!e&&!n.isEmpty()&&this.remove()}(e||!this.selection.isEmpty())&&this.insert(e,!0);if(t.restoreStart||t.restoreEnd){var n=this.selection.getRange();n.start.column-=t.restoreStart,n.end.column-=t.restoreEnd,this.selection.setRange(n)}},this.onCommandKey=function(e,t,n){this.keyBinding.onCommandKey(e,t,n)},this.setOverwrite=function(e){this.session.setOverwrite(e)},this.getOverwrite=function(){return this.session.getOverwrite()},this.toggleOverwrite=function(){this.session.toggleOverwrite()},this.setScrollSpeed=function(e){this.setOption("scrollSpeed",e)},this.getScrollSpeed=function(){return this.getOption("scrollSpeed")},this.setDragDelay=function(e){this.setOption("dragDelay",e)},this.getDragDelay=function(){return this.getOption("dragDelay")},this.setSelectionStyle=function(e){this.setOption("selectionStyle",e)},this.getSelectionStyle=function(){return this.getOption("selectionStyle")},this.setHighlightActiveLine=function(e){this.setOption("highlightActiveLine",e)},this.getHighlightActiveLine=function(){return this.getOption("highlightActiveLine")},this.setHighlightGutterLine=function(e){this.setOption("highlightGutterLine",e)},this.getHighlightGutterLine=function(){return this.getOption("highlightGutterLine")},this.setHighlightSelectedWord=function(e){this.setOption("highlightSelectedWord",e)},this.getHighlightSelectedWord=function(){return this.$highlightSelectedWord},this.setAnimatedScroll=function(e){this.renderer.setAnimatedScroll(e)},this.getAnimatedScroll=function(){return this.renderer.getAnimatedScroll()},this.setShowInvisibles=function(e){this.renderer.setShowInvisibles(e)},this.getShowInvisibles=function(){return this.renderer.getShowInvisibles()},this.setDisplayIndentGuides=function(e){this.renderer.setDisplayIndentGuides(e)},this.getDisplayIndentGuides=function(){return this.renderer.getDisplayIndentGuides()},this.setShowPrintMargin=function(e){this.renderer.setShowPrintMargin(e)},this.getShowPrintMargin=function(){return this.renderer.getShowPrintMargin()},this.setPrintMarginColumn=function(e){this.renderer.setPrintMarginColumn(e)},this.getPrintMarginColumn=function(){return this.renderer.getPrintMarginColumn()},this.setReadOnly=function(e){this.setOption("readOnly",e)},this.getReadOnly=function(){return this.getOption("readOnly")},this.setBehavioursEnabled=function(e){this.setOption("behavioursEnabled",e)},this.getBehavioursEnabled=function(){return this.getOption("behavioursEnabled")},this.setWrapBehavioursEnabled=function(e){this.setOption("wrapBehavioursEnabled",e)},this.getWrapBehavioursEnabled=function(){return this.getOption("wrapBehavioursEnabled")},this.setShowFoldWidgets=function(e){this.setOption("showFoldWidgets",e)},this.getShowFoldWidgets=function(){return this.getOption("showFoldWidgets")},this.setFadeFoldWidgets=function(e){this.setOption("fadeFoldWidgets",e)},this.getFadeFoldWidgets=function(){return this.getOption("fadeFoldWidgets")},this.remove=function(e){this.selection.isEmpty()&&(e=="left"?this.selection.selectLeft():this.selection.selectRight());var t=this.getSelectionRange();if(this.getBehavioursEnabled()){var n=this.session,r=n.getState(t.start.row),i=n.getMode().transformAction(r,"deletion",this,n,t);if(t.end.column===0){var s=n.getTextRange(t);if(s[s.length-1]=="\n"){var o=n.getLine(t.end.row);/^\s+$/.test(o)&&(t.end.column=o.length)}}i&&(t=i)}this.session.remove(t),this.clearSelection()},this.removeWordRight=function(){this.selection.isEmpty()&&this.selection.selectWordRight(),this.session.remove(this.getSelectionRange()),this.clearSelection()},this.removeWordLeft=function(){this.selection.isEmpty()&&this.selection.selectWordLeft(),this.session.remove(this.getSelectionRange()),this.clearSelection()},this.removeToLineStart=function(){this.selection.isEmpty()&&this.selection.selectLineStart(),this.selection.isEmpty()&&this.selection.selectLeft(),this.session.remove(this.getSelectionRange()),this.clearSelection()},this.removeToLineEnd=function(){this.selection.isEmpty()&&this.selection.selectLineEnd();var e=this.getSelectionRange();e.start.column==e.end.column&&e.start.row==e.end.row&&(e.end.column=0,e.end.row++),this.session.remove(e),this.clearSelection()},this.splitLine=function(){this.selection.isEmpty()||(this.session.remove(this.getSelectionRange()),this.clearSelection());var e=this.getCursorPosition();this.insert("\n"),this.moveCursorToPosition(e)},this.transposeLetters=function(){if(!this.selection.isEmpty())return;var e=this.getCursorPosition(),t=e.column;if(t===0)return;var n=this.session.getLine(e.row),r,i;tt.toLowerCase()?1:0});var i=new p(0,0,0,0);for(var r=e.first;r<=e.last;r++){var s=t.getLine(r);i.start.row=r,i.end.row=r,i.end.column=s.length,t.replace(i,n[r-e.first])}},this.toggleCommentLines=function(){var e=this.session.getState(this.getCursorPosition().row),t=this.$getSelectedRows();this.session.getMode().toggleCommentLines(e,this.session,t.first,t.last)},this.toggleBlockComment=function(){var e=this.getCursorPosition(),t=this.session.getState(e.row),n=this.getSelectionRange();this.session.getMode().toggleBlockComment(t,this.session,n,e)},this.getNumberAt=function(e,t){var n=/[\-]?[0-9]+(?:\.[0-9]+)?/g;n.lastIndex=0;var r=this.session.getLine(e);while(n.lastIndex=t){var s={value:i[0],start:i.index,end:i.index+i[0].length};return s}}return null},this.modifyNumber=function(e){var t=this.selection.getCursor().row,n=this.selection.getCursor().column,r=new p(t,n-1,t,n),i=this.session.getTextRange(r);if(!isNaN(parseFloat(i))&&isFinite(i)){var s=this.getNumberAt(t,n);if(s){var o=s.value.indexOf(".")>=0?s.start+s.value.indexOf(".")+1:s.end,u=s.start+s.value.length-o,a=parseFloat(s.value);a*=Math.pow(10,u),o!==s.end&&n=u&&o<=a&&(n=t,f.selection.clearSelection(),f.moveCursorTo(e,u+r),f.selection.selectTo(e,a+r)),u=a});var l=this.$toggleWordPairs,c;for(var h=0;hp+1)break;p=d.last}l--,u=this.session.$moveLines(h,p,t?0:e),t&&e==-1&&(c=l+1);while(c<=l)o[c].moveBy(u,0),c++;t||(u=0),a+=u}i.fromOrientedRange(i.ranges[0]),i.rangeList.attach(this.session),this.inVirtualSelectionMode=!1}},this.$getSelectedRows=function(e){return e=(e||this.getSelectionRange()).collapseRows(),{first:this.session.getRowFoldStart(e.start.row),last:this.session.getRowFoldEnd(e.end.row)}},this.onCompositionStart=function(e){this.renderer.showComposition(e)},this.onCompositionUpdate=function(e){this.renderer.setCompositionText(e)},this.onCompositionEnd=function(){this.renderer.hideComposition()},this.getFirstVisibleRow=function(){return this.renderer.getFirstVisibleRow()},this.getLastVisibleRow=function(){return this.renderer.getLastVisibleRow()},this.isRowVisible=function(e){return e>=this.getFirstVisibleRow()&&e<=this.getLastVisibleRow()},this.isRowFullyVisible=function(e){return e>=this.renderer.getFirstFullyVisibleRow()&&e<=this.renderer.getLastFullyVisibleRow()},this.$getVisibleRowCount=function(){return this.renderer.getScrollBottomRow()-this.renderer.getScrollTopRow()+1},this.$moveByPage=function(e,t){var n=this.renderer,r=this.renderer.layerConfig,i=e*Math.floor(r.height/r.lineHeight);t===!0?this.selection.$moveSelection(function(){this.moveCursorBy(i,0)}):t===!1&&(this.selection.moveCursorBy(i,0),this.selection.clearSelection());var s=n.scrollTop;n.scrollBy(0,i*r.lineHeight),t!=null&&n.scrollCursorIntoView(null,.5),n.animateScrolling(s)},this.selectPageDown=function(){this.$moveByPage(1,!0)},this.selectPageUp=function(){this.$moveByPage(-1,!0)},this.gotoPageDown=function(){this.$moveByPage(1,!1)},this.gotoPageUp=function(){this.$moveByPage(-1,!1)},this.scrollPageDown=function(){this.$moveByPage(1)},this.scrollPageUp=function(){this.$moveByPage(-1)},this.scrollToRow=function(e){this.renderer.scrollToRow(e)},this.scrollToLine=function(e,t,n,r){this.renderer.scrollToLine(e,t,n,r)},this.centerSelection=function(){var e=this.getSelectionRange(),t={row:Math.floor(e.start.row+(e.end.row-e.start.row)/2),column:Math.floor(e.start.column+(e.end.column-e.start.column)/2)};this.renderer.alignCursor(t,.5)},this.getCursorPosition=function(){return this.selection.getCursor()},this.getCursorPositionScreen=function(){return this.session.documentToScreenPosition(this.getCursorPosition())},this.getSelectionRange=function(){return this.selection.getRange()},this.selectAll=function(){this.selection.selectAll()},this.clearSelection=function(){this.selection.clearSelection()},this.moveCursorTo=function(e,t){this.selection.moveCursorTo(e,t)},this.moveCursorToPosition=function(e){this.selection.moveCursorToPosition(e)},this.jumpToMatching=function(e,t){var n=this.getCursorPosition(),r=new y(this.session,n.row,n.column),i=r.getCurrentToken(),s=i||r.stepForward();if(!s)return;var o,u=!1,a={},f=n.column-s.start,l,c={")":"(","(":"(","]":"[","[":"[","{":"{","}":"{"};do{if(s.value.match(/[{}()\[\]]/g))for(;f=0;--s)this.$tryReplace(n[s],e)&&r++;return this.selection.setSelectionRange(i),r},this.$tryReplace=function(e,t){var n=this.session.getTextRange(e);return t=this.$search.replace(n,t),t!==null?(e.end=this.session.replace(e,t),e):null},this.getLastSearchOptions=function(){return this.$search.getOptions()},this.find=function(e,t,n){t||(t={}),typeof e=="string"||e instanceof RegExp?t.needle=e:typeof e=="object"&&r.mixin(t,e);var i=this.selection.getRange();t.needle==null&&(e=this.session.getTextRange(i)||this.$search.$options.needle,e||(i=this.session.getWordRange(i.start.row,i.start.column),e=this.session.getTextRange(i)),this.$search.set({needle:e})),this.$search.set(t),t.start||this.$search.set({start:i});var s=this.$search.find(this.session);if(t.preventScroll)return s;if(s)return this.revealRange(s,n),s;t.backwards?i.start=i.end:i.end=i.start,this.selection.setRange(i)},this.findNext=function(e,t){this.find({skipCurrent:!0,backwards:!1},e,t)},this.findPrevious=function(e,t){this.find(e,{skipCurrent:!0,backwards:!0},t)},this.revealRange=function(e,t){this.session.unfold(e),this.selection.setSelectionRange(e);var n=this.renderer.scrollTop;this.renderer.scrollSelectionIntoView(e.start,e.end,.5),t!==!1&&this.renderer.animateScrolling(n)},this.undo=function(){this.session.getUndoManager().undo(this.session),this.renderer.scrollCursorIntoView(null,.5)},this.redo=function(){this.session.getUndoManager().redo(this.session),this.renderer.scrollCursorIntoView(null,.5)},this.destroy=function(){this.renderer.destroy(),this._signal("destroy",this),this.session&&this.session.destroy()},this.setAutoScrollEditorIntoView=function(e){if(!e)return;var t,n=this,r=!1;this.$scrollAnchor||(this.$scrollAnchor=document.createElement("div"));var i=this.$scrollAnchor;i.style.cssText="position:absolute",this.container.insertBefore(i,this.container.firstChild);var s=this.on("changeSelection",function(){r=!0}),o=this.renderer.on("beforeRender",function(){r&&(t=n.renderer.container.getBoundingClientRect())}),u=this.renderer.on("afterRender",function(){if(r&&t&&(n.isFocused()||n.searchBox&&n.searchBox.isFocused())){var e=n.renderer,s=e.$cursorLayer.$pixelPos,o=e.layerConfig,u=s.top-o.offset;s.top>=0&&u+t.top<0?r=!0:s.topwindow.innerHeight?r=!1:r=null,r!=null&&(i.style.top=u+"px",i.style.left=s.left+"px",i.style.height=o.lineHeight+"px",i.scrollIntoView(r)),r=t=null}});this.setAutoScrollEditorIntoView=function(e){if(e)return;delete this.setAutoScrollEditorIntoView,this.off("changeSelection",s),this.renderer.off("afterRender",u),this.renderer.off("beforeRender",o)}},this.$resetCursorStyle=function(){var e=this.$cursorStyle||"ace",t=this.renderer.$cursorLayer;if(!t)return;t.setSmoothBlinking(/smooth/.test(e)),t.isBlinking=!this.$readOnly&&e!="wide",i.setCssClass(t.element,"ace_slim-cursors",/slim/.test(e))},this.prompt=function(e,t,n){var r=this;g.loadModule("./ext/prompt",function(i){i.prompt(r,e,t,n)})}}.call(w.prototype),g.defineOptions(w.prototype,"editor",{selectionStyle:{set:function(e){this.onSelectionChange(),this._signal("changeSelectionStyle",{data:e})},initialValue:"line"},highlightActiveLine:{set:function(){this.$updateHighlightActiveLine()},initialValue:!0},highlightSelectedWord:{set:function(e){this.$onSelectionChange()},initialValue:!0},readOnly:{set:function(e){this.textInput.setReadOnly(e),this.$resetCursorStyle()},initialValue:!1},copyWithEmptySelection:{set:function(e){this.textInput.setCopyWithEmptySelection(e)},initialValue:!1},cursorStyle:{set:function(e){this.$resetCursorStyle()},values:["ace","slim","smooth","wide"],initialValue:"ace"},mergeUndoDeltas:{values:[!1,!0,"always"],initialValue:!0},behavioursEnabled:{initialValue:!0},wrapBehavioursEnabled:{initialValue:!0},autoScrollEditorIntoView:{set:function(e){this.setAutoScrollEditorIntoView(e)}},keyboardHandler:{set:function(e){this.setKeyboardHandler(e)},get:function(){return this.$keybindingId},handlesSet:!0},value:{set:function(e){this.session.setValue(e)},get:function(){return this.getValue()},handlesSet:!0,hidden:!0},session:{set:function(e){this.setSession(e)},get:function(){return this.session},handlesSet:!0,hidden:!0},showLineNumbers:{set:function(e){this.renderer.$gutterLayer.setShowLineNumbers(e),this.renderer.$loop.schedule(this.renderer.CHANGE_GUTTER),e&&this.$relativeLineNumbers?E.attach(this):E.detach(this)},initialValue:!0},relativeLineNumbers:{set:function(e){this.$showLineNumbers&&e?E.attach(this):E.detach(this)}},hScrollBarAlwaysVisible:"renderer",vScrollBarAlwaysVisible:"renderer",highlightGutterLine:"renderer",animatedScroll:"renderer",showInvisibles:"renderer",showPrintMargin:"renderer",printMarginColumn:"renderer",printMargin:"renderer",fadeFoldWidgets:"renderer",showFoldWidgets:"renderer",displayIndentGuides:"renderer",showGutter:"renderer",fontSize:"renderer",fontFamily:"renderer",maxLines:"renderer",minLines:"renderer",scrollPastEnd:"renderer",fixedWidthGutter:"renderer",theme:"renderer",hasCssTransforms:"renderer",maxPixelHeight:"renderer",useTextareaForIME:"renderer",scrollSpeed:"$mouseHandler",dragDelay:"$mouseHandler",dragEnabled:"$mouseHandler",focusTimeout:"$mouseHandler",tooltipFollowsMouse:"$mouseHandler",firstLineNumber:"session",overwrite:"session",newLineMode:"session",useWorker:"session",useSoftTabs:"session",navigateWithinSoftTabs:"session",tabSize:"session",wrap:"session",indentedSoftWrap:"session",foldStyle:"session",mode:"session"});var E={getText:function(e,t){return(Math.abs(e.selection.lead.row-t)||t+1+(t<9?"\u00b7":""))+""},getWidth:function(e,t,n){return Math.max(t.toString().length,(n.lastRow+1).toString().length,2)*n.characterWidth},update:function(e,t){t.renderer.$loop.schedule(t.renderer.CHANGE_GUTTER)},attach:function(e){e.renderer.$gutterLayer.$renderer=this,e.on("changeSelection",this.update),this.update(null,e)},detach:function(e){e.renderer.$gutterLayer.$renderer==this&&(e.renderer.$gutterLayer.$renderer=null),e.off("changeSelection",this.update),this.update(null,e)}};t.Editor=w}),ace.define("ace/undomanager",["require","exports","module","ace/range"],function(e,t,n){"use strict";function i(e,t){for(var n=t;n--;){var r=e[n];if(r&&!r[0].ignore){while(n0){a.row+=i,a.column+=a.row==r.row?s:0;continue}!t&&l<=0&&(a.row=n.row,a.column=n.column,l===0&&(a.bias=1))}}function f(e){return{row:e.row,column:e.column}}function l(e){return{start:f(e.start),end:f(e.end),action:e.action,lines:e.lines.slice()}}function c(e){e=e||this;if(Array.isArray(e))return e.map(c).join("\n");var t="";e.action?(t=e.action=="insert"?"+":"-",t+="["+e.lines+"]"):e.value&&(Array.isArray(e.value)?t=e.value.map(h).join("\n"):t=h(e.value)),e.start&&(t+=h(e));if(e.id||e.rev)t+=" ("+(e.id||e.rev)+")";return t}function h(e){return e.start.row+":"+e.start.column+"=>"+e.end.row+":"+e.end.column}function p(e,t){var n=e.action=="insert",r=t.action=="insert";if(n&&r)if(o(t.start,e.end)>=0)m(t,e,-1);else{if(!(o(t.start,e.start)<=0))return null;m(e,t,1)}else if(n&&!r)if(o(t.start,e.end)>=0)m(t,e,-1);else{if(!(o(t.end,e.start)<=0))return null;m(e,t,-1)}else if(!n&&r)if(o(t.start,e.start)>=0)m(t,e,1);else{if(!(o(t.start,e.start)<=0))return null;m(e,t,1)}else if(!n&&!r)if(o(t.start,e.start)>=0)m(t,e,1);else{if(!(o(t.end,e.start)<=0))return null;m(e,t,-1)}return[t,e]}function d(e,t){for(var n=e.length;n--;)for(var r=0;r=0?m(e,t,-1):o(e.start,t.start)<=0?m(t,e,1):(m(e,s.fromPoints(t.start,e.start),-1),m(t,e,1));else if(!n&&r)o(t.start,e.end)>=0?m(t,e,-1):o(t.start,e.start)<=0?m(e,t,1):(m(t,s.fromPoints(e.start,t.start),-1),m(e,t,1));else if(!n&&!r)if(o(t.start,e.end)>=0)m(t,e,-1);else{if(!(o(t.end,e.start)<=0)){var i,u;return o(e.start,t.start)<0&&(i=e,e=y(e,t.start)),o(e.end,t.end)>0&&(u=y(e,t.end)),g(t.end,e.start,e.end,-1),u&&!i&&(e.lines=u.lines,e.start=u.start,e.end=u.end,u=e),[t,i,u].filter(Boolean)}m(e,t,-1)}return[t,e]}function m(e,t,n){g(e.start,t.start,t.end,n),g(e.end,t.start,t.end,n)}function g(e,t,n,r){e.row==(r==1?t:n).row&&(e.column+=r*(n.column-t.column)),e.row+=r*(n.row-t.row)}function y(e,t){var n=e.lines,r=e.end;e.end=f(t);var i=e.end.row-e.start.row,s=n.splice(i,n.length),o=i?t.column:t.column-e.start.column;n.push(s[0].substring(0,o)),s[0]=s[0].substr(o);var u={start:f(t),end:r,lines:s,action:e.action};return u}function b(e,t){t=l(t);for(var n=e.length;n--;){var r=e[n];for(var i=0;i0},this.canRedo=function(){return this.$redoStack.length>0},this.bookmark=function(e){e==undefined&&(e=this.$rev),this.mark=e},this.isAtBookmark=function(){return this.$rev===this.mark},this.toJSON=function(){},this.fromJSON=function(){},this.hasUndo=this.canUndo,this.hasRedo=this.canRedo,this.isClean=this.isAtBookmark,this.markClean=this.bookmark,this.$prettyPrint=function(e){return e?c(e):c(this.$undoStack)+"\n---\n"+c(this.$redoStack)}}).call(r.prototype);var s=e("./range").Range,o=s.comparePoints,u=s.comparePoints;t.UndoManager=r}),ace.define("ace/layer/lines",["require","exports","module","ace/lib/dom"],function(e,t,n){"use strict";var r=e("../lib/dom"),i=function(e,t){this.element=e,this.canvasHeight=t||5e5,this.element.style.height=this.canvasHeight*2+"px",this.cells=[],this.cellCache=[],this.$offsetCoefficient=0};(function(){this.moveContainer=function(e){r.translate(this.element,0,-(e.firstRowScreen*e.lineHeight%this.canvasHeight)-e.offset*this.$offsetCoefficient)},this.pageChanged=function(e,t){return Math.floor(e.firstRowScreen*e.lineHeight/this.canvasHeight)!==Math.floor(t.firstRowScreen*t.lineHeight/this.canvasHeight)},this.computeLineTop=function(e,t,n){var r=t.firstRowScreen*t.lineHeight,i=Math.floor(r/this.canvasHeight),s=n.documentToScreenRow(e,0)*t.lineHeight;return s-i*this.canvasHeight},this.computeLineHeight=function(e,t,n){return t.lineHeight*n.getRowLength(e)},this.getLength=function(){return this.cells.length},this.get=function(e){return this.cells[e]},this.shift=function(){this.$cacheCell(this.cells.shift())},this.pop=function(){this.$cacheCell(this.cells.pop())},this.push=function(e){if(Array.isArray(e)){this.cells.push.apply(this.cells,e);var t=r.createFragment(this.element);for(var n=0;ns&&(a=i.end.row+1,i=t.getNextFoldLine(a,i),s=i?i.start.row:Infinity);if(a>r){while(this.$lines.getLength()>u+1)this.$lines.pop();break}o=this.$lines.get(++u),o?o.row=a:(o=this.$lines.createCell(a,e,this.session,f),this.$lines.push(o)),this.$renderCell(o,e,i,a),a++}this._signal("afterRender"),this.$updateGutterWidth(e)},this.$updateGutterWidth=function(e){var t=this.session,n=t.gutterRenderer||this.$renderer,r=t.$firstLineNumber,i=this.$lines.last()?this.$lines.last().text:"";if(this.$fixedWidth||t.$useWrapMode)i=t.getLength()+r-1;var s=n?n.getWidth(t,i,e):i.toString().length*e.characterWidth,o=this.$padding||this.$computePadding();s+=o.left+o.right,s!==this.gutterWidth&&!isNaN(s)&&(this.gutterWidth=s,this.element.parentNode.style.width=this.element.style.width=Math.ceil(this.gutterWidth)+"px",this._signal("changeGutterWidth",s))},this.$updateCursorRow=function(){if(!this.$highlightGutterLine)return;var e=this.session.selection.getCursor();if(this.$cursorRow===e.row)return;this.$cursorRow=e.row},this.updateLineHighlight=function(){if(!this.$highlightGutterLine)return;var e=this.session.selection.cursor.row;this.$cursorRow=e;if(this.$cursorCell&&this.$cursorCell.row==e)return;this.$cursorCell&&(this.$cursorCell.element.className=this.$cursorCell.element.className.replace("ace_gutter-active-line ",""));var t=this.$lines.cells;this.$cursorCell=null;for(var n=0;n=this.$cursorRow){if(r.row>this.$cursorRow){var i=this.session.getFoldLine(this.$cursorRow);if(!(n>0&&i&&i.start.row==t[n-1].row))break;r=t[n-1]}r.element.className="ace_gutter-active-line "+r.element.className,this.$cursorCell=r;break}}},this.scrollLines=function(e){var t=this.config;this.config=e,this.$updateCursorRow();if(this.$lines.pageChanged(t,e))return this.update(e);this.$lines.moveContainer(e);var n=Math.min(e.lastRow+e.gutterOffset,this.session.getLength()-1),r=this.oldLastRow;this.oldLastRow=n;if(!t||r0;i--)this.$lines.shift();if(r>n)for(var i=this.session.getFoldedRowCount(n+1,r);i>0;i--)this.$lines.pop();e.firstRowr&&this.$lines.push(this.$renderLines(e,r+1,n)),this.updateLineHighlight(),this._signal("afterRender"),this.$updateGutterWidth(e)},this.$renderLines=function(e,t,n){var r=[],i=t,s=this.session.getNextFoldLine(i),o=s?s.start.row:Infinity;for(;;){i>o&&(i=s.end.row+1,s=this.session.getNextFoldLine(i,s),o=s?s.start.row:Infinity);if(i>n)break;var u=this.$lines.createCell(i,e,this.session,f);this.$renderCell(u,e,s,i),r.push(u),i++}return r},this.$renderCell=function(e,t,n,i){var s=e.element,o=this.session,u=s.childNodes[0],a=s.childNodes[1],f=o.$firstLineNumber,l=o.$breakpoints,c=o.$decorations,h=o.gutterRenderer||this.$renderer,p=this.$showFoldWidgets&&o.foldWidgets,d=n?n.start.row:Number.MAX_VALUE,v="ace_gutter-cell ";this.$highlightGutterLine&&(i==this.$cursorRow||n&&i=d&&this.$cursorRow<=n.end.row)&&(v+="ace_gutter-active-line ",this.$cursorCell!=e&&(this.$cursorCell&&(this.$cursorCell.element.className=this.$cursorCell.element.className.replace("ace_gutter-active-line ","")),this.$cursorCell=e)),l[i]&&(v+=l[i]),c[i]&&(v+=c[i]),this.$annotations[i]&&(v+=this.$annotations[i].className),s.className!=v&&(s.className=v);if(p){var m=p[i];m==null&&(m=p[i]=o.getFoldWidget(i))}if(m){var v="ace_fold-widget ace_"+m;m=="start"&&i==d&&in.right-t.right)return"foldWidgets"}}).call(a.prototype),t.Gutter=a}),ace.define("ace/layer/marker",["require","exports","module","ace/range","ace/lib/dom"],function(e,t,n){"use strict";var r=e("../range").Range,i=e("../lib/dom"),s=function(e){this.element=i.createElement("div"),this.element.className="ace_layer ace_marker-layer",e.appendChild(this.element)};(function(){function e(e,t,n,r){return(e?1:0)|(t?2:0)|(n?4:0)|(r?8:0)}this.$padding=0,this.setPadding=function(e){this.$padding=e},this.setSession=function(e){this.session=e},this.setMarkers=function(e){this.markers=e},this.elt=function(e,t){var n=this.i!=-1&&this.element.childNodes[this.i];n?this.i++:(n=document.createElement("div"),this.element.appendChild(n),this.i=-1),n.style.cssText=t,n.className=e},this.update=function(e){if(!e)return;this.config=e,this.i=0;var t;for(var n in this.markers){var r=this.markers[n];if(!r.range){r.update(t,this,this.session,e);continue}var i=r.range.clipRows(e.firstRow,e.lastRow);if(i.isEmpty())continue;i=i.toScreenRange(this.session);if(r.renderer){var s=this.$getTop(i.start.row,e),o=this.$padding+i.start.column*e.characterWidth;r.renderer(t,i,o,s,e)}else r.type=="fullLine"?this.drawFullLineMarker(t,i,r.clazz,e):r.type=="screenLine"?this.drawScreenLineMarker(t,i,r.clazz,e):i.isMultiLine()?r.type=="text"?this.drawTextMarker(t,i,r.clazz,e):this.drawMultiLineMarker(t,i,r.clazz,e):this.drawSingleLineMarker(t,i,r.clazz+" ace_start"+" ace_br15",e)}if(this.i!=-1)while(this.ip,l==f),s,l==f?0:1,o)},this.drawMultiLineMarker=function(e,t,n,r,i){var s=this.$padding,o=r.lineHeight,u=this.$getTop(t.start.row,r),a=s+t.start.column*r.characterWidth;i=i||"";if(this.session.$bidiHandler.isBidiRow(t.start.row)){var f=t.clone();f.end.row=f.start.row,f.end.column=this.session.getLine(f.start.row).length,this.drawBidiSingleLineMarker(e,f,n+" ace_br1 ace_start",r,null,i)}else this.elt(n+" ace_br1 ace_start","height:"+o+"px;"+"right:0;"+"top:"+u+"px;left:"+a+"px;"+(i||""));if(this.session.$bidiHandler.isBidiRow(t.end.row)){var f=t.clone();f.start.row=f.end.row,f.start.column=0,this.drawBidiSingleLineMarker(e,f,n+" ace_br12",r,null,i)}else{u=this.$getTop(t.end.row,r);var l=t.end.column*r.characterWidth;this.elt(n+" ace_br12","height:"+o+"px;"+"width:"+l+"px;"+"top:"+u+"px;"+"left:"+s+"px;"+(i||""))}o=(t.end.row-t.start.row-1)*r.lineHeight;if(o<=0)return;u=this.$getTop(t.start.row+1,r);var c=(t.start.column?1:0)|(t.end.column?0:8);this.elt(n+(c?" ace_br"+c:""),"height:"+o+"px;"+"right:0;"+"top:"+u+"px;"+"left:"+s+"px;"+(i||""))},this.drawSingleLineMarker=function(e,t,n,r,i,s){if(this.session.$bidiHandler.isBidiRow(t.start.row))return this.drawBidiSingleLineMarker(e,t,n,r,i,s);var o=r.lineHeight,u=(t.end.column+(i||0)-t.start.column)*r.characterWidth,a=this.$getTop(t.start.row,r),f=this.$padding+t.start.column*r.characterWidth;this.elt(n,"height:"+o+"px;"+"width:"+u+"px;"+"top:"+a+"px;"+"left:"+f+"px;"+(s||""))},this.drawBidiSingleLineMarker=function(e,t,n,r,i,s){var o=r.lineHeight,u=this.$getTop(t.start.row,r),a=this.$padding,f=this.session.$bidiHandler.getSelections(t.start.column,t.end.column);f.forEach(function(e){this.elt(n,"height:"+o+"px;"+"width:"+e.width+(i||0)+"px;"+"top:"+u+"px;"+"left:"+(a+e.left)+"px;"+(s||""))},this)},this.drawFullLineMarker=function(e,t,n,r,i){var s=this.$getTop(t.start.row,r),o=r.lineHeight;t.start.row!=t.end.row&&(o+=this.$getTop(t.end.row,r)-s),this.elt(n,"height:"+o+"px;"+"top:"+s+"px;"+"left:0;right:0;"+(i||""))},this.drawScreenLineMarker=function(e,t,n,r,i){var s=this.$getTop(t.start.row,r),o=r.lineHeight;this.elt(n,"height:"+o+"px;"+"top:"+s+"px;"+"left:0;right:0;"+(i||""))}}).call(s.prototype),t.Marker=s}),ace.define("ace/layer/text",["require","exports","module","ace/lib/oop","ace/lib/dom","ace/lib/lang","ace/layer/lines","ace/lib/event_emitter"],function(e,t,n){"use strict";var r=e("../lib/oop"),i=e("../lib/dom"),s=e("../lib/lang"),o=e("./lines").Lines,u=e("../lib/event_emitter").EventEmitter,a=function(e){this.dom=i,this.element=this.dom.createElement("div"),this.element.className="ace_layer ace_text-layer",e.appendChild(this.element),this.$updateEolChar=this.$updateEolChar.bind(this),this.$lines=new o(this.element)};(function(){r.implement(this,u),this.EOF_CHAR="\u00b6",this.EOL_CHAR_LF="\u00ac",this.EOL_CHAR_CRLF="\u00a4",this.EOL_CHAR=this.EOL_CHAR_LF,this.TAB_CHAR="\u2014",this.SPACE_CHAR="\u00b7",this.$padding=0,this.MAX_LINE_LENGTH=1e4,this.$updateEolChar=function(){var e=this.session.doc,t=e.getNewLineCharacter()=="\n"&&e.getNewLineMode()!="windows",n=t?this.EOL_CHAR_LF:this.EOL_CHAR_CRLF;if(this.EOL_CHAR!=n)return this.EOL_CHAR=n,!0},this.setPadding=function(e){this.$padding=e,this.element.style.margin="0 "+e+"px"},this.getLineHeight=function(){return this.$fontMetrics.$characterSize.height||0},this.getCharacterWidth=function(){return this.$fontMetrics.$characterSize.width||0},this.$setFontMetrics=function(e){this.$fontMetrics=e,this.$fontMetrics.on("changeCharacterSize",function(e){this._signal("changeCharacterSize",e)}.bind(this)),this.$pollSizeChanges()},this.checkForSizeChanges=function(){this.$fontMetrics.checkForSizeChanges()},this.$pollSizeChanges=function(){return this.$pollSizeChangesTimer=this.$fontMetrics.$pollSizeChanges()},this.setSession=function(e){this.session=e,e&&this.$computeTabString()},this.showInvisibles=!1,this.setShowInvisibles=function(e){return this.showInvisibles==e?!1:(this.showInvisibles=e,this.$computeTabString(),!0)},this.displayIndentGuides=!0,this.setDisplayIndentGuides=function(e){return this.displayIndentGuides==e?!1:(this.displayIndentGuides=e,this.$computeTabString(),!0)},this.$tabStrings=[],this.onChangeTabSize=this.$computeTabString=function(){var e=this.session.getTabSize();this.tabSize=e;var t=this.$tabStrings=[0];for(var n=1;nl&&(u=a.end.row+1,a=this.session.getNextFoldLine(u,a),l=a?a.start.row:Infinity);if(u>i)break;var c=s[o++];if(c){this.dom.removeChildren(c),this.$renderLine(c,u,u==l?a:!1);var h=e.lineHeight*this.session.getRowLength(u)+"px";c.style.height!=h&&(f=!0,c.style.height=h)}u++}if(f)while(o0;i--)this.$lines.shift();if(t.lastRow>e.lastRow)for(var i=this.session.getFoldedRowCount(e.lastRow+1,t.lastRow);i>0;i--)this.$lines.pop();e.firstRowt.lastRow&&this.$lines.push(this.$renderLinesFragment(e,t.lastRow+1,e.lastRow))},this.$renderLinesFragment=function(e,t,n){var r=[],s=t,o=this.session.getNextFoldLine(s),u=o?o.start.row:Infinity;for(;;){s>u&&(s=o.end.row+1,o=this.session.getNextFoldLine(s,o),u=o?o.start.row:Infinity);if(s>n)break;var a=this.$lines.createCell(s,e,this.session),f=a.element;this.dom.removeChildren(f),i.setStyle(f.style,"height",this.$lines.computeLineHeight(s,e,this.session)+"px"),i.setStyle(f.style,"top",this.$lines.computeLineTop(s,e,this.session)+"px"),this.$renderLine(f,s,s==u?o:!1),this.$useLineGroups()?f.className="ace_line_group":f.className="ace_line",r.push(a),s++}return r},this.update=function(e){this.$lines.moveContainer(e),this.config=e;var t=e.firstRow,n=e.lastRow,r=this.$lines;while(r.getLength())r.pop();r.push(this.$renderLinesFragment(e,t,n))},this.$textToken={text:!0,rparen:!0,lparen:!0},this.$renderToken=function(e,t,n,r){var i=this,o=/(\t)|( +)|([\x00-\x1f\x80-\xa0\xad\u1680\u180E\u2000-\u200f\u2028\u2029\u202F\u205F\uFEFF\uFFF9-\uFFFC]+)|(\u3000)|([\u1100-\u115F\u11A3-\u11A7\u11FA-\u11FF\u2329-\u232A\u2E80-\u2E99\u2E9B-\u2EF3\u2F00-\u2FD5\u2FF0-\u2FFB\u3001-\u303E\u3041-\u3096\u3099-\u30FF\u3105-\u312D\u3131-\u318E\u3190-\u31BA\u31C0-\u31E3\u31F0-\u321E\u3220-\u3247\u3250-\u32FE\u3300-\u4DBF\u4E00-\uA48C\uA490-\uA4C6\uA960-\uA97C\uAC00-\uD7A3\uD7B0-\uD7C6\uD7CB-\uD7FB\uF900-\uFAFF\uFE10-\uFE19\uFE30-\uFE52\uFE54-\uFE66\uFE68-\uFE6B\uFF01-\uFF60\uFFE0-\uFFE6]|[\uD800-\uDBFF][\uDC00-\uDFFF])/g,u=this.dom.createFragment(this.element),a,f=0;while(a=o.exec(r)){var l=a[1],c=a[2],h=a[3],p=a[4],d=a[5];if(!i.showInvisibles&&c)continue;var v=f!=a.index?r.slice(f,a.index):"";f=a.index+a[0].length,v&&u.appendChild(this.dom.createTextNode(v,this.element));if(l){var m=i.session.getScreenTabSize(t+a.index);u.appendChild(i.$tabStrings[m].cloneNode(!0)),t+=m-1}else if(c)if(i.showInvisibles){var g=this.dom.createElement("span");g.className="ace_invisible ace_invisible_space",g.textContent=s.stringRepeat(i.SPACE_CHAR,c.length),u.appendChild(g)}else u.appendChild(this.com.createTextNode(c,this.element));else if(h){var g=this.dom.createElement("span");g.className="ace_invisible ace_invisible_space ace_invalid",g.textContent=s.stringRepeat(i.SPACE_CHAR,h.length),u.appendChild(g)}else if(p){var y=i.showInvisibles?i.SPACE_CHAR:"";t+=1;var g=this.dom.createElement("span");g.style.width=i.config.characterWidth*2+"px",g.className=i.showInvisibles?"ace_cjk ace_invisible ace_invisible_space":"ace_cjk",g.textContent=i.showInvisibles?i.SPACE_CHAR:"",u.appendChild(g)}else if(d){t+=1;var g=this.dom.createElement("span");g.style.width=i.config.characterWidth*2+"px",g.className="ace_cjk",g.textContent=d,u.appendChild(g)}}u.appendChild(this.dom.createTextNode(f?r.slice(f):r,this.element));if(!this.$textToken[n.type]){var b="ace_"+n.type.replace(/\./g," ace_"),g=this.dom.createElement("span");n.type=="fold"&&(g.style.width=n.value.length*this.config.characterWidth+"px"),g.className=b,g.appendChild(u),e.appendChild(g)}else e.appendChild(u);return t+r.length},this.renderIndentGuide=function(e,t,n){var r=t.search(this.$indentGuideRe);if(r<=0||r>=n)return t;if(t[0]==" "){r-=r%this.tabSize;var i=r/this.tabSize;for(var s=0;s=o)u=this.$renderToken(a,u,l,c.substring(0,o-r)),c=c.substring(o-r),r=o,a=this.$createLineElement(),e.appendChild(a),a.appendChild(this.dom.createTextNode(s.stringRepeat("\u00a0",n.indent),this.element)),i++,u=0,o=n[i]||Number.MAX_VALUE;c.length!=0&&(r+=c.length,u=this.$renderToken(a,u,l,c))}}n[n.length-1]>this.MAX_LINE_LENGTH&&this.$renderOverflowMessage(a,u,null,"",!0)},this.$renderSimpleLine=function(e,t){var n=0,r=t[0],i=r.value;this.displayIndentGuides&&(i=this.renderIndentGuide(e,i)),i&&(n=this.$renderToken(e,n,r,i));for(var s=1;sthis.MAX_LINE_LENGTH)return this.$renderOverflowMessage(e,n,r,i);n=this.$renderToken(e,n,r,i)}},this.$renderOverflowMessage=function(e,t,n,r,i){n&&this.$renderToken(e,t,n,r.slice(0,this.MAX_LINE_LENGTH-t));var s=this.dom.createElement("span");s.className="ace_inline_button ace_keyword ace_toggle_wrap",s.textContent=i?"":"",e.appendChild(s)},this.$renderLine=function(e,t,n){!n&&n!=0&&(n=this.session.getFoldLine(t));if(n)var r=this.$getFoldLineTokens(t,n);else var r=this.session.getTokens(t);var i=e;if(r.length){var s=this.session.getRowSplitData(t);if(s&&s.length){this.$renderWrappedLine(e,r,s);var i=e.lastChild}else{var i=e;this.$useLineGroups()&&(i=this.$createLineElement(),e.appendChild(i)),this.$renderSimpleLine(i,r)}}else this.$useLineGroups()&&(i=this.$createLineElement(),e.appendChild(i));if(this.showInvisibles&&i){n&&(t=n.end.row);var o=this.dom.createElement("span");o.className="ace_invisible ace_invisible_eol",o.textContent=t==this.session.getLength()-1?this.EOF_CHAR:this.EOL_CHAR,i.appendChild(o)}},this.$getFoldLineTokens=function(e,t){function i(e,t,n){var i=0,s=0;while(s+e[i].value.lengthn-t&&(o=o.substring(0,n-t)),r.push({type:e[i].type,value:o}),s=t+o.length,i+=1}while(sn?r.push({type:e[i].type,value:o.substring(0,n-s)}):r.push(e[i]),s+=o.length,i+=1}}var n=this.session,r=[],s=n.getTokens(e);return t.walk(function(e,t,o,u,a){e!=null?r.push({type:"fold",value:e}):(a&&(s=n.getTokens(t)),s.length&&i(s,u,o))},t.end.row,this.session.getLine(t.end.row).length),r},this.$useLineGroups=function(){return this.session.getUseWrapMode()},this.destroy=function(){}}).call(a.prototype),t.Text=a}),ace.define("ace/layer/cursor",["require","exports","module","ace/lib/dom"],function(e,t,n){"use strict";var r=e("../lib/dom"),i=function(e){this.element=r.createElement("div"),this.element.className="ace_layer ace_cursor-layer",e.appendChild(this.element),this.isVisible=!1,this.isBlinking=!0,this.blinkInterval=1e3,this.smoothBlinking=!1,this.cursors=[],this.cursor=this.addCursor(),r.addCssClass(this.element,"ace_hidden-cursors"),this.$updateCursors=this.$updateOpacity.bind(this)};(function(){this.$updateOpacity=function(e){var t=this.cursors;for(var n=t.length;n--;)r.setStyle(t[n].style,"opacity",e?"":"0")},this.$startCssAnimation=function(){var e=this.cursors;for(var t=e.length;t--;)e[t].style.animationDuration=this.blinkInterval+"ms";setTimeout(function(){r.addCssClass(this.element,"ace_animate-blinking")}.bind(this))},this.$stopCssAnimation=function(){r.removeCssClass(this.element,"ace_animate-blinking")},this.$padding=0,this.setPadding=function(e){this.$padding=e},this.setSession=function(e){this.session=e},this.setBlinking=function(e){e!=this.isBlinking&&(this.isBlinking=e,this.restartTimer())},this.setBlinkInterval=function(e){e!=this.blinkInterval&&(this.blinkInterval=e,this.restartTimer())},this.setSmoothBlinking=function(e){e!=this.smoothBlinking&&(this.smoothBlinking=e,r.setCssClass(this.element,"ace_smooth-blinking",e),this.$updateCursors(!0),this.restartTimer())},this.addCursor=function(){var e=r.createElement("div");return e.className="ace_cursor",this.element.appendChild(e),this.cursors.push(e),e},this.removeCursor=function(){if(this.cursors.length>1){var e=this.cursors.pop();return e.parentNode.removeChild(e),e}},this.hideCursor=function(){this.isVisible=!1,r.addCssClass(this.element,"ace_hidden-cursors"),this.restartTimer()},this.showCursor=function(){this.isVisible=!0,r.removeCssClass(this.element,"ace_hidden-cursors"),this.restartTimer()},this.restartTimer=function(){var e=this.$updateCursors;clearInterval(this.intervalId),clearTimeout(this.timeoutId),this.$stopCssAnimation(),this.smoothBlinking&&r.removeCssClass(this.element,"ace_smooth-blinking"),e(!0);if(!this.isBlinking||!this.blinkInterval||!this.isVisible){this.$stopCssAnimation();return}this.smoothBlinking&&setTimeout(function(){r.addCssClass(this.element,"ace_smooth-blinking")}.bind(this));if(r.HAS_CSS_ANIMATION)this.$startCssAnimation();else{var t=function(){this.timeoutId=setTimeout(function(){e(!1)},.6*this.blinkInterval)}.bind(this);this.intervalId=setInterval(function(){e(!0),t()},this.blinkInterval),t()}},this.getPixelPosition=function(e,t){if(!this.config||!this.session)return{left:0,top:0};e||(e=this.session.selection.getCursor());var n=this.session.documentToScreenPosition(e),r=this.$padding+(this.session.$bidiHandler.isBidiRow(n.row,e.row)?this.session.$bidiHandler.getPosLeft(n.column):n.column*this.config.characterWidth),i=(n.row-(t?this.config.firstRowScreen:0))*this.config.lineHeight;return{left:r,top:i}},this.isCursorInView=function(e,t){return e.top>=0&&e.tope.height+e.offset||o.top<0)&&n>1)continue;var u=this.cursors[i++]||this.addCursor(),a=u.style;this.drawCursor?this.drawCursor(u,o,e,t[n],this.session):this.isCursorInView(o,e)?(r.setStyle(a,"display","block"),r.translate(u,o.left,o.top),r.setStyle(a,"width",Math.round(e.characterWidth)+"px"),r.setStyle(a,"height",e.lineHeight+"px")):r.setStyle(a,"display","none")}while(this.cursors.length>i)this.removeCursor();var f=this.session.getOverwrite();this.$setOverwrite(f),this.$pixelPos=o,this.restartTimer()},this.drawCursor=null,this.$setOverwrite=function(e){e!=this.overwrite&&(this.overwrite=e,e?r.addCssClass(this.element,"ace_overwrite-cursors"):r.removeCssClass(this.element,"ace_overwrite-cursors"))},this.destroy=function(){clearInterval(this.intervalId),clearTimeout(this.timeoutId)}}).call(i.prototype),t.Cursor=i}),ace.define("ace/scrollbar",["require","exports","module","ace/lib/oop","ace/lib/dom","ace/lib/event","ace/lib/event_emitter"],function(e,t,n){"use strict";var r=e("./lib/oop"),i=e("./lib/dom"),s=e("./lib/event"),o=e("./lib/event_emitter").EventEmitter,u=32768,a=function(e){this.element=i.createElement("div"),this.element.className="ace_scrollbar ace_scrollbar"+this.classSuffix,this.inner=i.createElement("div"),this.inner.className="ace_scrollbar-inner",this.inner.textContent="\u00a0",this.element.appendChild(this.inner),e.appendChild(this.element),this.setVisible(!1),this.skipEvent=!1,s.addListener(this.element,"scroll",this.onScroll.bind(this)),s.addListener(this.element,"mousedown",s.preventDefault)};(function(){r.implement(this,o),this.setVisible=function(e){this.element.style.display=e?"":"none",this.isVisible=e,this.coeff=1}}).call(a.prototype);var f=function(e,t){a.call(this,e),this.scrollTop=0,this.scrollHeight=0,t.$scrollbarWidth=this.width=i.scrollbarWidth(e.ownerDocument),this.inner.style.width=this.element.style.width=(this.width||15)+5+"px",this.$minWidth=0};r.inherits(f,a),function(){this.classSuffix="-v",this.onScroll=function(){if(!this.skipEvent){this.scrollTop=this.element.scrollTop;if(this.coeff!=1){var e=this.element.clientHeight/this.scrollHeight;this.scrollTop=this.scrollTop*(1-e)/(this.coeff-e)}this._emit("scroll",{data:this.scrollTop})}this.skipEvent=!1},this.getWidth=function(){return Math.max(this.isVisible?this.width:0,this.$minWidth||0)},this.setHeight=function(e){this.element.style.height=e+"px"},this.setInnerHeight=this.setScrollHeight=function(e){this.scrollHeight=e,e>u?(this.coeff=u/e,e=u):this.coeff!=1&&(this.coeff=1),this.inner.style.height=e+"px"},this.setScrollTop=function(e){this.scrollTop!=e&&(this.skipEvent=!0,this.scrollTop=e,this.element.scrollTop=e*this.coeff)}}.call(f.prototype);var l=function(e,t){a.call(this,e),this.scrollLeft=0,this.height=t.$scrollbarWidth,this.inner.style.height=this.element.style.height=(this.height||15)+5+"px"};r.inherits(l,a),function(){this.classSuffix="-h",this.onScroll=function(){this.skipEvent||(this.scrollLeft=this.element.scrollLeft,this._emit("scroll",{data:this.scrollLeft})),this.skipEvent=!1},this.getHeight=function(){return this.isVisible?this.height:0},this.setWidth=function(e){this.element.style.width=e+"px"},this.setInnerWidth=function(e){this.inner.style.width=e+"px"},this.setScrollWidth=function(e){this.inner.style.width=e+"px"},this.setScrollLeft=function(e){this.scrollLeft!=e&&(this.skipEvent=!0,this.scrollLeft=this.element.scrollLeft=e)}}.call(l.prototype),t.ScrollBar=f,t.ScrollBarV=f,t.ScrollBarH=l,t.VScrollBar=f,t.HScrollBar=l}),ace.define("ace/renderloop",["require","exports","module","ace/lib/event"],function(e,t,n){"use strict";var r=e("./lib/event"),i=function(e,t){this.onRender=e,this.pending=!1,this.changes=0,this.$recursionLimit=2,this.window=t||window;var n=this;this._flush=function(e){n.pending=!1;var t=n.changes;t&&(r.blockIdle(100),n.changes=0,n.onRender(t));if(n.changes){if(n.$recursionLimit--<0)return;n.schedule()}else n.$recursionLimit=2}};(function(){this.schedule=function(e){this.changes=this.changes|e,this.changes&&!this.pending&&(r.nextFrame(this._flush),this.pending=!0)},this.clear=function(e){var t=this.changes;return this.changes=0,t}}).call(i.prototype),t.RenderLoop=i}),ace.define("ace/layer/font_metrics",["require","exports","module","ace/lib/oop","ace/lib/dom","ace/lib/lang","ace/lib/event","ace/lib/useragent","ace/lib/event_emitter"],function(e,t,n){var r=e("../lib/oop"),i=e("../lib/dom"),s=e("../lib/lang"),o=e("../lib/event"),u=e("../lib/useragent"),a=e("../lib/event_emitter").EventEmitter,f=256,l=typeof ResizeObserver=="function",c=200,h=t.FontMetrics=function(e){this.el=i.createElement("div"),this.$setMeasureNodeStyles(this.el.style,!0),this.$main=i.createElement("div"),this.$setMeasureNodeStyles(this.$main.style),this.$measureNode=i.createElement("div"),this.$setMeasureNodeStyles(this.$measureNode.style),this.el.appendChild(this.$main),this.el.appendChild(this.$measureNode),e.appendChild(this.el),this.$measureNode.innerHTML=s.stringRepeat("X",f),this.$characterSize={width:0,height:0},l?this.$addObserver():this.checkForSizeChanges()};(function(){r.implement(this,a),this.$characterSize={width:0,height:0},this.$setMeasureNodeStyles=function(e,t){e.width=e.height="auto",e.left=e.top="0px",e.visibility="hidden",e.position="absolute",e.whiteSpace="pre",u.isIE<8?e["font-family"]="inherit":e.font="inherit",e.overflow=t?"hidden":"visible"},this.checkForSizeChanges=function(e){e===undefined&&(e=this.$measureSizes());if(e&&(this.$characterSize.width!==e.width||this.$characterSize.height!==e.height)){this.$measureNode.style.fontWeight="bold";var t=this.$measureSizes();this.$measureNode.style.fontWeight="",this.$characterSize=e,this.charSizes=Object.create(null),this.allowBoldFonts=t&&t.width===e.width&&t.height===e.height,this._emit("changeCharacterSize",{data:e})}},this.$addObserver=function(){var e=this;this.$observer=new window.ResizeObserver(function(t){var n=t[0].contentRect;e.checkForSizeChanges({height:n.height,width:n.width/f})}),this.$observer.observe(this.$measureNode)},this.$pollSizeChanges=function(){if(this.$pollSizeChangesTimer||this.$observer)return this.$pollSizeChangesTimer;var e=this;return this.$pollSizeChangesTimer=o.onIdle(function t(){e.checkForSizeChanges(),o.onIdle(t,500)},500)},this.setPolling=function(e){e?this.$pollSizeChanges():this.$pollSizeChangesTimer&&(clearInterval(this.$pollSizeChangesTimer),this.$pollSizeChangesTimer=0)},this.$measureSizes=function(e){var t={height:(e||this.$measureNode).clientHeight,width:(e||this.$measureNode).clientWidth/f};return t.width===0||t.height===0?null:t},this.$measureCharWidth=function(e){this.$main.innerHTML=s.stringRepeat(e,f);var t=this.$main.getBoundingClientRect();return t.width/f},this.getCharacterWidth=function(e){var t=this.charSizes[e];return t===undefined&&(t=this.charSizes[e]=this.$measureCharWidth(e)/this.$characterSize.width),t},this.destroy=function(){clearInterval(this.$pollSizeChangesTimer),this.$observer&&this.$observer.disconnect(),this.el&&this.el.parentNode&&this.el.parentNode.removeChild(this.el)},this.$getZoom=function e(t){return t?(window.getComputedStyle(t).zoom||1)*e(t.parentElement):1},this.$initTransformMeasureNodes=function(){var e=function(e,t){return["div",{style:"position: absolute;top:"+e+"px;left:"+t+"px;"}]};this.els=i.buildDom([e(0,0),e(c,0),e(0,c),e(c,c)],this.el)},this.transformCoordinates=function(e,t){function r(e,t,n){var r=e[1]*t[0]-e[0]*t[1];return[(-t[1]*n[0]+t[0]*n[1])/r,(+e[1]*n[0]-e[0]*n[1])/r]}function i(e,t){return[e[0]-t[0],e[1]-t[1]]}function s(e,t){return[e[0]+t[0],e[1]+t[1]]}function o(e,t){return[e*t[0],e*t[1]]}function u(e){var t=e.getBoundingClientRect();return[t.left,t.top]}if(e){var n=this.$getZoom(this.el);e=o(1/n,e)}this.els||this.$initTransformMeasureNodes();var a=u(this.els[0]),f=u(this.els[1]),l=u(this.els[2]),h=u(this.els[3]),p=r(i(h,f),i(h,l),i(s(f,l),s(h,a))),d=o(1+p[0],i(f,a)),v=o(1+p[1],i(l,a));if(t){var m=t,g=p[0]*m[0]/c+p[1]*m[1]/c+1,y=s(o(m[0],d),o(m[1],v));return s(o(1/g/c,y),a)}var b=i(e,a),w=r(i(d,o(p[0],b)),i(v,o(p[1],b)),b);return o(c,w)}}).call(h.prototype)}),ace.define("ace/virtual_renderer",["require","exports","module","ace/lib/oop","ace/lib/dom","ace/config","ace/layer/gutter","ace/layer/marker","ace/layer/text","ace/layer/cursor","ace/scrollbar","ace/scrollbar","ace/renderloop","ace/layer/font_metrics","ace/lib/event_emitter","ace/lib/useragent"],function(e,t,n){"use strict";var r=e("./lib/oop"),i=e("./lib/dom"),s=e("./config"),o=e("./layer/gutter").Gutter,u=e("./layer/marker").Marker,a=e("./layer/text").Text,f=e("./layer/cursor").Cursor,l=e("./scrollbar").HScrollBar,c=e("./scrollbar").VScrollBar,h=e("./renderloop").RenderLoop,p=e("./layer/font_metrics").FontMetrics,d=e("./lib/event_emitter").EventEmitter,v='.ace_br1 {border-top-left-radius : 3px;}.ace_br2 {border-top-right-radius : 3px;}.ace_br3 {border-top-left-radius : 3px; border-top-right-radius: 3px;}.ace_br4 {border-bottom-right-radius: 3px;}.ace_br5 {border-top-left-radius : 3px; border-bottom-right-radius: 3px;}.ace_br6 {border-top-right-radius : 3px; border-bottom-right-radius: 3px;}.ace_br7 {border-top-left-radius : 3px; border-top-right-radius: 3px; border-bottom-right-radius: 3px;}.ace_br8 {border-bottom-left-radius : 3px;}.ace_br9 {border-top-left-radius : 3px; border-bottom-left-radius: 3px;}.ace_br10{border-top-right-radius : 3px; border-bottom-left-radius: 3px;}.ace_br11{border-top-left-radius : 3px; border-top-right-radius: 3px; border-bottom-left-radius: 3px;}.ace_br12{border-bottom-right-radius: 3px; border-bottom-left-radius: 3px;}.ace_br13{border-top-left-radius : 3px; border-bottom-right-radius: 3px; border-bottom-left-radius: 3px;}.ace_br14{border-top-right-radius : 3px; border-bottom-right-radius: 3px; border-bottom-left-radius: 3px;}.ace_br15{border-top-left-radius : 3px; border-top-right-radius: 3px; border-bottom-right-radius: 3px; border-bottom-left-radius: 3px;}.ace_editor {position: relative;overflow: hidden;font: 12px/normal \'Monaco\', \'Menlo\', \'Ubuntu Mono\', \'Consolas\', \'source-code-pro\', monospace;direction: ltr;text-align: left;-webkit-tap-highlight-color: rgba(0, 0, 0, 0);}.ace_scroller {position: absolute;overflow: hidden;top: 0;bottom: 0;background-color: inherit;-ms-user-select: none;-moz-user-select: none;-webkit-user-select: none;user-select: none;cursor: text;}.ace_content {position: absolute;box-sizing: border-box;min-width: 100%;contain: style size layout;}.ace_dragging .ace_scroller:before{position: absolute;top: 0;left: 0;right: 0;bottom: 0;content: \'\';background: rgba(250, 250, 250, 0.01);z-index: 1000;}.ace_dragging.ace_dark .ace_scroller:before{background: rgba(0, 0, 0, 0.01);}.ace_selecting, .ace_selecting * {cursor: text !important;}.ace_gutter {position: absolute;overflow : hidden;width: auto;top: 0;bottom: 0;left: 0;cursor: default;z-index: 4;-ms-user-select: none;-moz-user-select: none;-webkit-user-select: none;user-select: none;contain: style size layout;}.ace_gutter-active-line {position: absolute;left: 0;right: 0;}.ace_scroller.ace_scroll-left {box-shadow: 17px 0 16px -16px rgba(0, 0, 0, 0.4) inset;}.ace_gutter-cell {position: absolute;top: 0;left: 0;right: 0;padding-left: 19px;padding-right: 6px;background-repeat: no-repeat;}.ace_gutter-cell.ace_error {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAMAAAAoLQ9TAAABOFBMVEX/////////QRswFAb/Ui4wFAYwFAYwFAaWGAfDRymzOSH/PxswFAb/SiUwFAYwFAbUPRvjQiDllog5HhHdRybsTi3/Tyv9Tir+Syj/UC3////XurebMBIwFAb/RSHbPx/gUzfdwL3kzMivKBAwFAbbvbnhPx66NhowFAYwFAaZJg8wFAaxKBDZurf/RB6mMxb/SCMwFAYwFAbxQB3+RB4wFAb/Qhy4Oh+4QifbNRcwFAYwFAYwFAb/QRzdNhgwFAYwFAbav7v/Uy7oaE68MBK5LxLewr/r2NXewLswFAaxJw4wFAbkPRy2PyYwFAaxKhLm1tMwFAazPiQwFAaUGAb/QBrfOx3bvrv/VC/maE4wFAbRPBq6MRO8Qynew8Dp2tjfwb0wFAbx6eju5+by6uns4uH9/f36+vr/GkHjAAAAYnRSTlMAGt+64rnWu/bo8eAA4InH3+DwoN7j4eLi4xP99Nfg4+b+/u9B/eDs1MD1mO7+4PHg2MXa347g7vDizMLN4eG+Pv7i5evs/v79yu7S3/DV7/498Yv24eH+4ufQ3Ozu/v7+y13sRqwAAADLSURBVHjaZc/XDsFgGIBhtDrshlitmk2IrbHFqL2pvXf/+78DPokj7+Fz9qpU/9UXJIlhmPaTaQ6QPaz0mm+5gwkgovcV6GZzd5JtCQwgsxoHOvJO15kleRLAnMgHFIESUEPmawB9ngmelTtipwwfASilxOLyiV5UVUyVAfbG0cCPHig+GBkzAENHS0AstVF6bacZIOzgLmxsHbt2OecNgJC83JERmePUYq8ARGkJx6XtFsdddBQgZE2nPR6CICZhawjA4Fb/chv+399kfR+MMMDGOQAAAABJRU5ErkJggg==");background-repeat: no-repeat;background-position: 2px center;}.ace_gutter-cell.ace_warning {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAMAAAAoLQ9TAAAAmVBMVEX///8AAAD///8AAAAAAABPSzb/5sAAAAB/blH/73z/ulkAAAAAAAD85pkAAAAAAAACAgP/vGz/rkDerGbGrV7/pkQICAf////e0IsAAAD/oED/qTvhrnUAAAD/yHD/njcAAADuv2r/nz//oTj/p064oGf/zHAAAAA9Nir/tFIAAAD/tlTiuWf/tkIAAACynXEAAAAAAAAtIRW7zBpBAAAAM3RSTlMAABR1m7RXO8Ln31Z36zT+neXe5OzooRDfn+TZ4p3h2hTf4t3k3ucyrN1K5+Xaks52Sfs9CXgrAAAAjklEQVR42o3PbQ+CIBQFYEwboPhSYgoYunIqqLn6/z8uYdH8Vmdnu9vz4WwXgN/xTPRD2+sgOcZjsge/whXZgUaYYvT8QnuJaUrjrHUQreGczuEafQCO/SJTufTbroWsPgsllVhq3wJEk2jUSzX3CUEDJC84707djRc5MTAQxoLgupWRwW6UB5fS++NV8AbOZgnsC7BpEAAAAABJRU5ErkJggg==");background-position: 2px center;}.ace_gutter-cell.ace_info {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABAAAAAQCAAAAAA6mKC9AAAAGXRFWHRTb2Z0d2FyZQBBZG9iZSBJbWFnZVJlYWR5ccllPAAAAAJ0Uk5TAAB2k804AAAAPklEQVQY02NgIB68QuO3tiLznjAwpKTgNyDbMegwisCHZUETUZV0ZqOquBpXj2rtnpSJT1AEnnRmL2OgGgAAIKkRQap2htgAAAAASUVORK5CYII=");background-position: 2px center;}.ace_dark .ace_gutter-cell.ace_info {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABAAAAAQBAMAAADt3eJSAAAAJFBMVEUAAAChoaGAgIAqKiq+vr6tra1ZWVmUlJSbm5s8PDxubm56enrdgzg3AAAAAXRSTlMAQObYZgAAAClJREFUeNpjYMAPdsMYHegyJZFQBlsUlMFVCWUYKkAZMxZAGdxlDMQBAG+TBP4B6RyJAAAAAElFTkSuQmCC");}.ace_scrollbar {contain: strict;position: absolute;right: 0;bottom: 0;z-index: 6;}.ace_scrollbar-inner {position: absolute;cursor: text;left: 0;top: 0;}.ace_scrollbar-v{overflow-x: hidden;overflow-y: scroll;top: 0;}.ace_scrollbar-h {overflow-x: scroll;overflow-y: hidden;left: 0;}.ace_print-margin {position: absolute;height: 100%;}.ace_text-input {position: absolute;z-index: 0;width: 0.5em;height: 1em;opacity: 0;background: transparent;-moz-appearance: none;appearance: none;border: none;resize: none;outline: none;overflow: hidden;font: inherit;padding: 0 1px;margin: 0 -1px;contain: strict;-ms-user-select: text;-moz-user-select: text;-webkit-user-select: text;user-select: text;white-space: pre!important;}.ace_text-input.ace_composition {background: transparent;color: inherit;z-index: 1000;opacity: 1;}.ace_composition_placeholder { color: transparent }.ace_composition_marker { border-bottom: 1px solid;position: absolute;border-radius: 0;margin-top: 1px;}[ace_nocontext=true] {transform: none!important;filter: none!important;perspective: none!important;clip-path: none!important;mask : none!important;contain: none!important;perspective: none!important;mix-blend-mode: initial!important;z-index: auto;}.ace_layer {z-index: 1;position: absolute;overflow: hidden;word-wrap: normal;white-space: pre;height: 100%;width: 100%;box-sizing: border-box;pointer-events: none;}.ace_gutter-layer {position: relative;width: auto;text-align: right;pointer-events: auto;height: 1000000px;contain: style size layout;}.ace_text-layer {font: inherit !important;position: absolute;height: 1000000px;width: 1000000px;contain: style size layout;}.ace_text-layer > .ace_line, .ace_text-layer > .ace_line_group {contain: style size layout;position: absolute;top: 0;left: 0;right: 0;}.ace_hidpi .ace_text-layer,.ace_hidpi .ace_gutter-layer,.ace_hidpi .ace_content,.ace_hidpi .ace_gutter {contain: strict;will-change: transform;}.ace_hidpi .ace_text-layer > .ace_line, .ace_hidpi .ace_text-layer > .ace_line_group {contain: strict;}.ace_cjk {display: inline-block;text-align: center;}.ace_cursor-layer {z-index: 4;}.ace_cursor {z-index: 4;position: absolute;box-sizing: border-box;border-left: 2px solid;transform: translatez(0);}.ace_multiselect .ace_cursor {border-left-width: 1px;}.ace_slim-cursors .ace_cursor {border-left-width: 1px;}.ace_overwrite-cursors .ace_cursor {border-left-width: 0;border-bottom: 1px solid;}.ace_hidden-cursors .ace_cursor {opacity: 0.2;}.ace_smooth-blinking .ace_cursor {transition: opacity 0.18s;}.ace_animate-blinking .ace_cursor {animation-duration: 1000ms;animation-timing-function: step-end;animation-name: blink-ace-animate;animation-iteration-count: infinite;}.ace_animate-blinking.ace_smooth-blinking .ace_cursor {animation-duration: 1000ms;animation-timing-function: ease-in-out;animation-name: blink-ace-animate-smooth;}@keyframes blink-ace-animate {from, to { opacity: 1; }60% { opacity: 0; }}@keyframes blink-ace-animate-smooth {from, to { opacity: 1; }45% { opacity: 1; }60% { opacity: 0; }85% { opacity: 0; }}.ace_marker-layer .ace_step, .ace_marker-layer .ace_stack {position: absolute;z-index: 3;}.ace_marker-layer .ace_selection {position: absolute;z-index: 5;}.ace_marker-layer .ace_bracket {position: absolute;z-index: 6;}.ace_marker-layer .ace_active-line {position: absolute;z-index: 2;}.ace_marker-layer .ace_selected-word {position: absolute;z-index: 4;box-sizing: border-box;}.ace_line .ace_fold {box-sizing: border-box;display: inline-block;height: 11px;margin-top: -2px;vertical-align: middle;background-image:url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABEAAAAJCAYAAADU6McMAAAAGXRFWHRTb2Z0d2FyZQBBZG9iZSBJbWFnZVJlYWR5ccllPAAAAJpJREFUeNpi/P//PwOlgAXGYGRklAVSokD8GmjwY1wasKljQpYACtpCFeADcHVQfQyMQAwzwAZI3wJKvCLkfKBaMSClBlR7BOQikCFGQEErIH0VqkabiGCAqwUadAzZJRxQr/0gwiXIal8zQQPnNVTgJ1TdawL0T5gBIP1MUJNhBv2HKoQHHjqNrA4WO4zY0glyNKLT2KIfIMAAQsdgGiXvgnYAAAAASUVORK5CYII="),url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAEAAAA3CAYAAADNNiA5AAAAGXRFWHRTb2Z0d2FyZQBBZG9iZSBJbWFnZVJlYWR5ccllPAAAACJJREFUeNpi+P//fxgTAwPDBxDxD078RSX+YeEyDFMCIMAAI3INmXiwf2YAAAAASUVORK5CYII=");background-repeat: no-repeat, repeat-x;background-position: center center, top left;color: transparent;border: 1px solid black;border-radius: 2px;cursor: pointer;pointer-events: auto;}.ace_dark .ace_fold {}.ace_fold:hover{background-image:url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAABEAAAAJCAYAAADU6McMAAAAGXRFWHRTb2Z0d2FyZQBBZG9iZSBJbWFnZVJlYWR5ccllPAAAAJpJREFUeNpi/P//PwOlgAXGYGRklAVSokD8GmjwY1wasKljQpYACtpCFeADcHVQfQyMQAwzwAZI3wJKvCLkfKBaMSClBlR7BOQikCFGQEErIH0VqkabiGCAqwUadAzZJRxQr/0gwiXIal8zQQPnNVTgJ1TdawL0T5gBIP1MUJNhBv2HKoQHHjqNrA4WO4zY0glyNKLT2KIfIMAAQsdgGiXvgnYAAAAASUVORK5CYII="),url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAEAAAA3CAYAAADNNiA5AAAAGXRFWHRTb2Z0d2FyZQBBZG9iZSBJbWFnZVJlYWR5ccllPAAAACBJREFUeNpi+P//fz4TAwPDZxDxD5X4i5fLMEwJgAADAEPVDbjNw87ZAAAAAElFTkSuQmCC");}.ace_tooltip {background-color: #FFF;background-image: linear-gradient(to bottom, transparent, rgba(0, 0, 0, 0.1));border: 1px solid gray;border-radius: 1px;box-shadow: 0 1px 2px rgba(0, 0, 0, 0.3);color: black;max-width: 100%;padding: 3px 4px;position: fixed;z-index: 999999;box-sizing: border-box;cursor: default;white-space: pre;word-wrap: break-word;line-height: normal;font-style: normal;font-weight: normal;letter-spacing: normal;pointer-events: none;}.ace_folding-enabled > .ace_gutter-cell {padding-right: 13px;}.ace_fold-widget {box-sizing: border-box;margin: 0 -12px 0 1px;display: none;width: 11px;vertical-align: top;background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAUAAAAFCAYAAACNbyblAAAANElEQVR42mWKsQ0AMAzC8ixLlrzQjzmBiEjp0A6WwBCSPgKAXoLkqSot7nN3yMwR7pZ32NzpKkVoDBUxKAAAAABJRU5ErkJggg==");background-repeat: no-repeat;background-position: center;border-radius: 3px;border: 1px solid transparent;cursor: pointer;}.ace_folding-enabled .ace_fold-widget {display: inline-block; }.ace_fold-widget.ace_end {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAUAAAAFCAYAAACNbyblAAAANElEQVR42m3HwQkAMAhD0YzsRchFKI7sAikeWkrxwScEB0nh5e7KTPWimZki4tYfVbX+MNl4pyZXejUO1QAAAABJRU5ErkJggg==");}.ace_fold-widget.ace_closed {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAMAAAAGCAYAAAAG5SQMAAAAOUlEQVR42jXKwQkAMAgDwKwqKD4EwQ26sSOkVWjgIIHAzPiCgaqiqnJHZnKICBERHN194O5b9vbLuAVRL+l0YWnZAAAAAElFTkSuQmCCXA==");}.ace_fold-widget:hover {border: 1px solid rgba(0, 0, 0, 0.3);background-color: rgba(255, 255, 255, 0.2);box-shadow: 0 1px 1px rgba(255, 255, 255, 0.7);}.ace_fold-widget:active {border: 1px solid rgba(0, 0, 0, 0.4);background-color: rgba(0, 0, 0, 0.05);box-shadow: 0 1px 1px rgba(255, 255, 255, 0.8);}.ace_dark .ace_fold-widget {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAUAAAAFCAYAAACNbyblAAAAHklEQVQIW2P4//8/AzoGEQ7oGCaLLAhWiSwB146BAQCSTPYocqT0AAAAAElFTkSuQmCC");}.ace_dark .ace_fold-widget.ace_end {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAUAAAAFCAYAAACNbyblAAAAH0lEQVQIW2P4//8/AxQ7wNjIAjDMgC4AxjCVKBirIAAF0kz2rlhxpAAAAABJRU5ErkJggg==");}.ace_dark .ace_fold-widget.ace_closed {background-image: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAMAAAAFCAYAAACAcVaiAAAAHElEQVQIW2P4//+/AxAzgDADlOOAznHAKgPWAwARji8UIDTfQQAAAABJRU5ErkJggg==");}.ace_dark .ace_fold-widget:hover {box-shadow: 0 1px 1px rgba(255, 255, 255, 0.2);background-color: rgba(255, 255, 255, 0.1);}.ace_dark .ace_fold-widget:active {box-shadow: 0 1px 1px rgba(255, 255, 255, 0.2);}.ace_inline_button {border: 1px solid lightgray;display: inline-block;margin: -1px 8px;padding: 0 5px;pointer-events: auto;cursor: pointer;}.ace_inline_button:hover {border-color: gray;background: rgba(200,200,200,0.2);display: inline-block;pointer-events: auto;}.ace_fold-widget.ace_invalid {background-color: #FFB4B4;border-color: #DE5555;}.ace_fade-fold-widgets .ace_fold-widget {transition: opacity 0.4s ease 0.05s;opacity: 0;}.ace_fade-fold-widgets:hover .ace_fold-widget {transition: opacity 0.05s ease 0.05s;opacity:1;}.ace_underline {text-decoration: underline;}.ace_bold {font-weight: bold;}.ace_nobold .ace_bold {font-weight: normal;}.ace_italic {font-style: italic;}.ace_error-marker {background-color: rgba(255, 0, 0,0.2);position: absolute;z-index: 9;}.ace_highlight-marker {background-color: rgba(255, 255, 0,0.2);position: absolute;z-index: 8;}',m=e("./lib/useragent"),g=m.isIE;i.importCssString(v,"ace_editor.css");var y=function(e,t){var n=this;this.container=e||i.createElement("div"),i.addCssClass(this.container,"ace_editor"),i.HI_DPI&&i.addCssClass(this.container,"ace_hidpi"),this.setTheme(t),this.$gutter=i.createElement("div"),this.$gutter.className="ace_gutter",this.container.appendChild(this.$gutter),this.$gutter.setAttribute("aria-hidden",!0),this.scroller=i.createElement("div"),this.scroller.className="ace_scroller",this.container.appendChild(this.scroller),this.content=i.createElement("div"),this.content.className="ace_content",this.scroller.appendChild(this.content),this.$gutterLayer=new o(this.$gutter),this.$gutterLayer.on("changeGutterWidth",this.onGutterResize.bind(this)),this.$markerBack=new u(this.content);var r=this.$textLayer=new a(this.content);this.canvas=r.element,this.$markerFront=new u(this.content),this.$cursorLayer=new f(this.content),this.$horizScroll=!1,this.$vScroll=!1,this.scrollBar=this.scrollBarV=new c(this.container,this),this.scrollBarH=new l(this.container,this),this.scrollBarV.addEventListener("scroll",function(e){n.$scrollAnimation||n.session.setScrollTop(e.data-n.scrollMargin.top)}),this.scrollBarH.addEventListener("scroll",function(e){n.$scrollAnimation||n.session.setScrollLeft(e.data-n.scrollMargin.left)}),this.scrollTop=0,this.scrollLeft=0,this.cursorPos={row:0,column:0},this.$fontMetrics=new p(this.container),this.$textLayer.$setFontMetrics(this.$fontMetrics),this.$textLayer.addEventListener("changeCharacterSize",function(e){n.updateCharacterSize(),n.onResize(!0,n.gutterWidth,n.$size.width,n.$size.height),n._signal("changeCharacterSize",e)}),this.$size={width:0,height:0,scrollerHeight:0,scrollerWidth:0,$dirty:!0},this.layerConfig={width:1,padding:0,firstRow:0,firstRowScreen:0,lastRow:0,lineHeight:0,characterWidth:0,minHeight:1,maxHeight:1,offset:0,height:1,gutterOffset:1},this.scrollMargin={left:0,right:0,top:0,bottom:0,v:0,h:0},this.margin={left:0,right:0,top:0,bottom:0,v:0,h:0},this.$keepTextAreaAtCursor=!m.isIOS,this.$loop=new h(this.$renderChanges.bind(this),this.container.ownerDocument.defaultView),this.$loop.schedule(this.CHANGE_FULL),this.updateCharacterSize(),this.setPadding(4),s.resetOptions(this),s._signal("renderer",this)};(function(){this.CHANGE_CURSOR=1,this.CHANGE_MARKER=2,this.CHANGE_GUTTER=4,this.CHANGE_SCROLL=8,this.CHANGE_LINES=16,this.CHANGE_TEXT=32,this.CHANGE_SIZE=64,this.CHANGE_MARKER_BACK=128,this.CHANGE_MARKER_FRONT=256,this.CHANGE_FULL=512,this.CHANGE_H_SCROLL=1024,r.implement(this,d),this.updateCharacterSize=function(){this.$textLayer.allowBoldFonts!=this.$allowBoldFonts&&(this.$allowBoldFonts=this.$textLayer.allowBoldFonts,this.setStyle("ace_nobold",!this.$allowBoldFonts)),this.layerConfig.characterWidth=this.characterWidth=this.$textLayer.getCharacterWidth(),this.layerConfig.lineHeight=this.lineHeight=this.$textLayer.getLineHeight(),this.$updatePrintMargin()},this.setSession=function(e){this.session&&this.session.doc.off("changeNewLineMode",this.onChangeNewLineMode),this.session=e,e&&this.scrollMargin.top&&e.getScrollTop()<=0&&e.setScrollTop(-this.scrollMargin.top),this.$cursorLayer.setSession(e),this.$markerBack.setSession(e),this.$markerFront.setSession(e),this.$gutterLayer.setSession(e),this.$textLayer.setSession(e);if(!e)return;this.$loop.schedule(this.CHANGE_FULL),this.session.$setFontMetrics(this.$fontMetrics),this.scrollBarH.scrollLeft=this.scrollBarV.scrollTop=null,this.onChangeNewLineMode=this.onChangeNewLineMode.bind(this),this.onChangeNewLineMode(),this.session.doc.on("changeNewLineMode",this.onChangeNewLineMode)},this.updateLines=function(e,t,n){t===undefined&&(t=Infinity),this.$changedLines?(this.$changedLines.firstRow>e&&(this.$changedLines.firstRow=e),this.$changedLines.lastRowthis.layerConfig.lastRow)return;this.$loop.schedule(this.CHANGE_LINES)},this.onChangeNewLineMode=function(){this.$loop.schedule(this.CHANGE_TEXT),this.$textLayer.$updateEolChar(),this.session.$bidiHandler.setEolChar(this.$textLayer.EOL_CHAR)},this.onChangeTabSize=function(){this.$loop.schedule(this.CHANGE_TEXT|this.CHANGE_MARKER),this.$textLayer.onChangeTabSize()},this.updateText=function(){this.$loop.schedule(this.CHANGE_TEXT)},this.updateFull=function(e){e?this.$renderChanges(this.CHANGE_FULL,!0):this.$loop.schedule(this.CHANGE_FULL)},this.updateFontSize=function(){this.$textLayer.checkForSizeChanges()},this.$changes=0,this.$updateSizeAsync=function(){this.$loop.pending?this.$size.$dirty=!0:this.onResize()},this.onResize=function(e,t,n,r){if(this.resizing>2)return;this.resizing>0?this.resizing++:this.resizing=e?1:0;var i=this.container;r||(r=i.clientHeight||i.scrollHeight),n||(n=i.clientWidth||i.scrollWidth);var s=this.$updateCachedSize(e,t,n,r);if(!this.$size.scrollerHeight||!n&&!r)return this.resizing=0;e&&(this.$gutterLayer.$padding=null),e?this.$renderChanges(s|this.$changes,!0):this.$loop.schedule(s|this.$changes),this.resizing&&(this.resizing=0),this.scrollBarV.scrollLeft=this.scrollBarV.scrollTop=null},this.$updateCachedSize=function(e,t,n,r){r-=this.$extraHeight||0;var s=0,o=this.$size,u={width:o.width,height:o.height,scrollerHeight:o.scrollerHeight,scrollerWidth:o.scrollerWidth};r&&(e||o.height!=r)&&(o.height=r,s|=this.CHANGE_SIZE,o.scrollerHeight=o.height,this.$horizScroll&&(o.scrollerHeight-=this.scrollBarH.getHeight()),this.scrollBarV.element.style.bottom=this.scrollBarH.getHeight()+"px",s|=this.CHANGE_SCROLL);if(n&&(e||o.width!=n)){s|=this.CHANGE_SIZE,o.width=n,t==null&&(t=this.$showGutter?this.$gutter.offsetWidth:0),this.gutterWidth=t,i.setStyle(this.scrollBarH.element.style,"left",t+"px"),i.setStyle(this.scroller.style,"left",t+this.margin.left+"px"),o.scrollerWidth=Math.max(0,n-t-this.scrollBarV.getWidth()-this.margin.h),i.setStyle(this.$gutter.style,"left",this.margin.left+"px");var a=this.scrollBarV.getWidth()+"px";i.setStyle(this.scrollBarH.element.style,"right",a),i.setStyle(this.scroller.style,"right",a),i.setStyle(this.scroller.style,"bottom",this.scrollBarH.getHeight());if(this.session&&this.session.getUseWrapMode()&&this.adjustWrapLimit()||e)s|=this.CHANGE_FULL}return o.$dirty=!n||!r,s&&this._signal("resize",u),s},this.onGutterResize=function(e){var t=this.$showGutter?e:0;t!=this.gutterWidth&&(this.$changes|=this.$updateCachedSize(!0,t,this.$size.width,this.$size.height)),this.session.getUseWrapMode()&&this.adjustWrapLimit()?this.$loop.schedule(this.CHANGE_FULL):this.$size.$dirty?this.$loop.schedule(this.CHANGE_FULL):this.$computeLayerConfig()},this.adjustWrapLimit=function(){var e=this.$size.scrollerWidth-this.$padding*2,t=Math.floor(e/this.characterWidth);return this.session.adjustWrapLimit(t,this.$showPrintMargin&&this.$printMarginColumn)},this.setAnimatedScroll=function(e){this.setOption("animatedScroll",e)},this.getAnimatedScroll=function(){return this.$animatedScroll},this.setShowInvisibles=function(e){this.setOption("showInvisibles",e),this.session.$bidiHandler.setShowInvisibles(e)},this.getShowInvisibles=function(){return this.getOption("showInvisibles")},this.getDisplayIndentGuides=function(){return this.getOption("displayIndentGuides")},this.setDisplayIndentGuides=function(e){this.setOption("displayIndentGuides",e)},this.setShowPrintMargin=function(e){this.setOption("showPrintMargin",e)},this.getShowPrintMargin=function(){return this.getOption("showPrintMargin")},this.setPrintMarginColumn=function(e){this.setOption("printMarginColumn",e)},this.getPrintMarginColumn=function(){return this.getOption("printMarginColumn")},this.getShowGutter=function(){return this.getOption("showGutter")},this.setShowGutter=function(e){return this.setOption("showGutter",e)},this.getFadeFoldWidgets=function(){return this.getOption("fadeFoldWidgets")},this.setFadeFoldWidgets=function(e){this.setOption("fadeFoldWidgets",e)},this.setHighlightGutterLine=function(e){this.setOption("highlightGutterLine",e)},this.getHighlightGutterLine=function(){return this.getOption("highlightGutterLine")},this.$updatePrintMargin=function(){if(!this.$showPrintMargin&&!this.$printMarginEl)return;if(!this.$printMarginEl){var e=i.createElement("div");e.className="ace_layer ace_print-margin-layer",this.$printMarginEl=i.createElement("div"),this.$printMarginEl.className="ace_print-margin",e.appendChild(this.$printMarginEl),this.content.insertBefore(e,this.content.firstChild)}var t=this.$printMarginEl.style;t.left=Math.round(this.characterWidth*this.$printMarginColumn+this.$padding)+"px",t.visibility=this.$showPrintMargin?"visible":"hidden",this.session&&this.session.$wrap==-1&&this.adjustWrapLimit()},this.getContainerElement=function(){return this.container},this.getMouseEventTarget=function(){return this.scroller},this.getTextAreaContainer=function(){return this.container},this.$moveTextAreaToCursor=function(){if(this.$isMousePressed)return;var e=this.textarea.style,t=this.$composition;if(!this.$keepTextAreaAtCursor&&!t){i.translate(this.textarea,-100,0);return}var n=this.$cursorLayer.$pixelPos;if(!n)return;t&&t.markerRange&&(n=this.$cursorLayer.getPixelPosition(t.markerRange.start,!0));var r=this.layerConfig,s=n.top,o=n.left;s-=r.offset;var u=t&&t.useTextareaForIME?this.lineHeight:g?0:1;if(s<0||s>r.height-u){i.translate(this.textarea,0,0);return}var a=1;if(!t)s+=this.lineHeight;else if(t.useTextareaForIME){var f=this.textarea.value;a=this.characterWidth*this.session.$getStringScreenWidth(f)[0],u+=2}else s+=this.lineHeight+2;o-=this.scrollLeft,o>this.$size.scrollerWidth-a&&(o=this.$size.scrollerWidth-a),o+=this.gutterWidth+this.margin.left,i.setStyle(e,"height",u+"px"),i.setStyle(e,"width",a+"px"),i.translate(this.textarea,Math.min(o,this.$size.scrollerWidth-a),Math.min(s,this.$size.height-u))},this.getFirstVisibleRow=function(){return this.layerConfig.firstRow},this.getFirstFullyVisibleRow=function(){return this.layerConfig.firstRow+(this.layerConfig.offset===0?0:1)},this.getLastFullyVisibleRow=function(){var e=this.layerConfig,t=e.lastRow,n=this.session.documentToScreenRow(t,0)*e.lineHeight;return n-this.session.getScrollTop()>e.height-e.lineHeight?t-1:t},this.getLastVisibleRow=function(){return this.layerConfig.lastRow},this.$padding=null,this.setPadding=function(e){this.$padding=e,this.$textLayer.setPadding(e),this.$cursorLayer.setPadding(e),this.$markerFront.setPadding(e),this.$markerBack.setPadding(e),this.$loop.schedule(this.CHANGE_FULL),this.$updatePrintMargin()},this.setScrollMargin=function(e,t,n,r){var i=this.scrollMargin;i.top=e|0,i.bottom=t|0,i.right=r|0,i.left=n|0,i.v=i.top+i.bottom,i.h=i.left+i.right,i.top&&this.scrollTop<=0&&this.session&&this.session.setScrollTop(-i.top),this.updateFull()},this.setMargin=function(e,t,n,r){var i=this.margin;i.top=e|0,i.bottom=t|0,i.right=r|0,i.left=n|0,i.v=i.top+i.bottom,i.h=i.left+i.right,this.$updateCachedSize(!0,this.gutterWidth,this.$size.width,this.$size.height),this.updateFull()},this.getHScrollBarAlwaysVisible=function(){return this.$hScrollBarAlwaysVisible},this.setHScrollBarAlwaysVisible=function(e){this.setOption("hScrollBarAlwaysVisible",e)},this.getVScrollBarAlwaysVisible=function(){return this.$vScrollBarAlwaysVisible},this.setVScrollBarAlwaysVisible=function(e){this.setOption("vScrollBarAlwaysVisible",e)},this.$updateScrollBarV=function(){var e=this.layerConfig.maxHeight,t=this.$size.scrollerHeight;!this.$maxLines&&this.$scrollPastEnd&&(e-=(t-this.lineHeight)*this.$scrollPastEnd,this.scrollTop>e-t&&(e=this.scrollTop+t,this.scrollBarV.scrollTop=null)),this.scrollBarV.setScrollHeight(e+this.scrollMargin.v),this.scrollBarV.setScrollTop(this.scrollTop+this.scrollMargin.top)},this.$updateScrollBarH=function(){this.scrollBarH.setScrollWidth(this.layerConfig.width+2*this.$padding+this.scrollMargin.h),this.scrollBarH.setScrollLeft(this.scrollLeft+this.scrollMargin.left)},this.$frozen=!1,this.freeze=function(){this.$frozen=!0},this.unfreeze=function(){this.$frozen=!1},this.$renderChanges=function(e,t){this.$changes&&(e|=this.$changes,this.$changes=0);if(!this.session||!this.container.offsetWidth||this.$frozen||!e&&!t){this.$changes|=e;return}if(this.$size.$dirty)return this.$changes|=e,this.onResize(!0);this.lineHeight||this.$textLayer.checkForSizeChanges(),this._signal("beforeRender"),this.session&&this.session.$bidiHandler&&this.session.$bidiHandler.updateCharacterWidths(this.$fontMetrics);var n=this.layerConfig;if(e&this.CHANGE_FULL||e&this.CHANGE_SIZE||e&this.CHANGE_TEXT||e&this.CHANGE_LINES||e&this.CHANGE_SCROLL||e&this.CHANGE_H_SCROLL){e|=this.$computeLayerConfig()|this.$loop.clear();if(n.firstRow!=this.layerConfig.firstRow&&n.firstRowScreen==this.layerConfig.firstRowScreen){var r=this.scrollTop+(n.firstRow-this.layerConfig.firstRow)*this.lineHeight;r>0&&(this.scrollTop=r,e|=this.CHANGE_SCROLL,e|=this.$computeLayerConfig()|this.$loop.clear())}n=this.layerConfig,this.$updateScrollBarV(),e&this.CHANGE_H_SCROLL&&this.$updateScrollBarH(),i.translate(this.content,-this.scrollLeft,-n.offset);var s=n.width+2*this.$padding+"px",o=n.minHeight+"px";i.setStyle(this.content.style,"width",s),i.setStyle(this.content.style,"height",o)}e&this.CHANGE_H_SCROLL&&(i.translate(this.content,-this.scrollLeft,-n.offset),this.scroller.className=this.scrollLeft<=0?"ace_scroller":"ace_scroller ace_scroll-left");if(e&this.CHANGE_FULL){this.$textLayer.update(n),this.$showGutter&&this.$gutterLayer.update(n),this.$markerBack.update(n),this.$markerFront.update(n),this.$cursorLayer.update(n),this.$moveTextAreaToCursor(),this._signal("afterRender");return}if(e&this.CHANGE_SCROLL){e&this.CHANGE_TEXT||e&this.CHANGE_LINES?this.$textLayer.update(n):this.$textLayer.scrollLines(n),this.$showGutter&&(e&this.CHANGE_GUTTER||e&this.CHANGE_LINES?this.$gutterLayer.update(n):this.$gutterLayer.scrollLines(n)),this.$markerBack.update(n),this.$markerFront.update(n),this.$cursorLayer.update(n),this.$moveTextAreaToCursor(),this._signal("afterRender");return}e&this.CHANGE_TEXT?(this.$textLayer.update(n),this.$showGutter&&this.$gutterLayer.update(n)):e&this.CHANGE_LINES?(this.$updateLines()||e&this.CHANGE_GUTTER&&this.$showGutter)&&this.$gutterLayer.update(n):e&this.CHANGE_TEXT||e&this.CHANGE_GUTTER?this.$showGutter&&this.$gutterLayer.update(n):e&this.CHANGE_CURSOR&&this.$highlightGutterLine&&this.$gutterLayer.updateLineHighlight(n),e&this.CHANGE_CURSOR&&(this.$cursorLayer.update(n),this.$moveTextAreaToCursor()),e&(this.CHANGE_MARKER|this.CHANGE_MARKER_FRONT)&&this.$markerFront.update(n),e&(this.CHANGE_MARKER|this.CHANGE_MARKER_BACK)&&this.$markerBack.update(n),this._signal("afterRender")},this.$autosize=function(){var e=this.session.getScreenLength()*this.lineHeight,t=this.$maxLines*this.lineHeight,n=Math.min(t,Math.max((this.$minLines||1)*this.lineHeight,e))+this.scrollMargin.v+(this.$extraHeight||0);this.$horizScroll&&(n+=this.scrollBarH.getHeight()),this.$maxPixelHeight&&n>this.$maxPixelHeight&&(n=this.$maxPixelHeight);var r=n<=2*this.lineHeight,i=!r&&e>t;if(n!=this.desiredHeight||this.$size.height!=this.desiredHeight||i!=this.$vScroll){i!=this.$vScroll&&(this.$vScroll=i,this.scrollBarV.setVisible(i));var s=this.container.clientWidth;this.container.style.height=n+"px",this.$updateCachedSize(!0,this.$gutterWidth,s,n),this.desiredHeight=n,this._signal("autosize")}},this.$computeLayerConfig=function(){var e=this.session,t=this.$size,n=t.height<=2*this.lineHeight,r=this.session.getScreenLength(),i=r*this.lineHeight,s=this.$getLongestLine(),o=!n&&(this.$hScrollBarAlwaysVisible||t.scrollerWidth-s-2*this.$padding<0),u=this.$horizScroll!==o;u&&(this.$horizScroll=o,this.scrollBarH.setVisible(o));var a=this.$vScroll;this.$maxLines&&this.lineHeight>1&&this.$autosize();var f=t.scrollerHeight+this.lineHeight,l=!this.$maxLines&&this.$scrollPastEnd?(t.scrollerHeight-this.lineHeight)*this.$scrollPastEnd:0;i+=l;var c=this.scrollMargin;this.session.setScrollTop(Math.max(-c.top,Math.min(this.scrollTop,i-t.scrollerHeight+c.bottom))),this.session.setScrollLeft(Math.max(-c.left,Math.min(this.scrollLeft,s+2*this.$padding-t.scrollerWidth+c.right)));var h=!n&&(this.$vScrollBarAlwaysVisible||t.scrollerHeight-i+l<0||this.scrollTop>c.top),p=a!==h;p&&(this.$vScroll=h,this.scrollBarV.setVisible(h));var d=this.scrollTop%this.lineHeight,v=Math.ceil(f/this.lineHeight)-1,m=Math.max(0,Math.round((this.scrollTop-d)/this.lineHeight)),g=m+v,y,b,w=this.lineHeight;m=e.screenToDocumentRow(m,0);var E=e.getFoldLine(m);E&&(m=E.start.row),y=e.documentToScreenRow(m,0),b=e.getRowLength(m)*w,g=Math.min(e.screenToDocumentRow(g,0),e.getLength()-1),f=t.scrollerHeight+e.getRowLength(g)*w+b,d=this.scrollTop-y*w;var S=0;if(this.layerConfig.width!=s||u)S=this.CHANGE_H_SCROLL;if(u||p)S|=this.$updateCachedSize(!0,this.gutterWidth,t.width,t.height),this._signal("scrollbarVisibilityChanged"),p&&(s=this.$getLongestLine());return this.layerConfig={width:s,padding:this.$padding,firstRow:m,firstRowScreen:y,lastRow:g,lineHeight:w,characterWidth:this.characterWidth,minHeight:f,maxHeight:i,offset:d,gutterOffset:w?Math.max(0,Math.ceil((d+t.height-t.scrollerHeight)/w)):0,height:this.$size.scrollerHeight},this.session.$bidiHandler&&this.session.$bidiHandler.setContentWidth(s-this.$padding),S},this.$updateLines=function(){if(!this.$changedLines)return;var e=this.$changedLines.firstRow,t=this.$changedLines.lastRow;this.$changedLines=null;var n=this.layerConfig;if(e>n.lastRow+1)return;if(tthis.$textLayer.MAX_LINE_LENGTH&&(e=this.$textLayer.MAX_LINE_LENGTH+30),Math.max(this.$size.scrollerWidth-2*this.$padding,Math.round(e*this.characterWidth))},this.updateFrontMarkers=function(){this.$markerFront.setMarkers(this.session.getMarkers(!0)),this.$loop.schedule(this.CHANGE_MARKER_FRONT)},this.updateBackMarkers=function(){this.$markerBack.setMarkers(this.session.getMarkers()),this.$loop.schedule(this.CHANGE_MARKER_BACK)},this.addGutterDecoration=function(e,t){this.$gutterLayer.addGutterDecoration(e,t)},this.removeGutterDecoration=function(e,t){this.$gutterLayer.removeGutterDecoration(e,t)},this.updateBreakpoints=function(e){this.$loop.schedule(this.CHANGE_GUTTER)},this.setAnnotations=function(e){this.$gutterLayer.setAnnotations(e),this.$loop.schedule(this.CHANGE_GUTTER)},this.updateCursor=function(){this.$loop.schedule(this.CHANGE_CURSOR)},this.hideCursor=function(){this.$cursorLayer.hideCursor()},this.showCursor=function(){this.$cursorLayer.showCursor()},this.scrollSelectionIntoView=function(e,t,n){this.scrollCursorIntoView(e,n),this.scrollCursorIntoView(t,n)},this.scrollCursorIntoView=function(e,t,n){if(this.$size.scrollerHeight===0)return;var r=this.$cursorLayer.getPixelPosition(e),i=r.left,s=r.top,o=n&&n.top||0,u=n&&n.bottom||0,a=this.$scrollAnimation?this.session.getScrollTop():this.scrollTop;a+o>s?(t&&a+o>s+this.lineHeight&&(s-=t*this.$size.scrollerHeight),s===0&&(s=-this.scrollMargin.top),this.session.setScrollTop(s)):a+this.$size.scrollerHeight-ui?(i=1-this.scrollMargin.top)return!0;if(t>0&&this.session.getScrollTop()+this.$size.scrollerHeight-this.layerConfig.maxHeight<-1+this.scrollMargin.bottom)return!0;if(e<0&&this.session.getScrollLeft()>=1-this.scrollMargin.left)return!0;if(e>0&&this.session.getScrollLeft()+this.$size.scrollerWidth-this.layerConfig.width<-1+this.scrollMargin.right)return!0},this.pixelToScreenCoordinates=function(e,t){var n;if(this.$hasCssTransforms){n={top:0,left:0};var r=this.$fontMetrics.transformCoordinates([e,t]);e=r[1]-this.gutterWidth-this.margin.left,t=r[0]}else n=this.scroller.getBoundingClientRect();var i=e+this.scrollLeft-n.left-this.$padding,s=i/this.characterWidth,o=Math.floor((t+this.scrollTop-n.top)/this.lineHeight),u=this.$blockCursor?Math.floor(s):Math.round(s);return{row:o,column:u,side:s-u>0?1:-1,offsetX:i}},this.screenToTextCoordinates=function(e,t){var n;if(this.$hasCssTransforms){n={top:0,left:0};var r=this.$fontMetrics.transformCoordinates([e,t]);e=r[1]-this.gutterWidth-this.margin.left,t=r[0]}else n=this.scroller.getBoundingClientRect();var i=e+this.scrollLeft-n.left-this.$padding,s=i/this.characterWidth,o=this.$blockCursor?Math.floor(s):Math.round(s),u=Math.floor((t+this.scrollTop-n.top)/this.lineHeight);return this.session.screenToDocumentPosition(u,Math.max(o,0),i)},this.textToScreenCoordinates=function(e,t){var n=this.scroller.getBoundingClientRect(),r=this.session.documentToScreenPosition(e,t),i=this.$padding+(this.session.$bidiHandler.isBidiRow(r.row,e)?this.session.$bidiHandler.getPosLeft(r.column):Math.round(r.column*this.characterWidth)),s=r.row*this.lineHeight;return{pageX:n.left+i-this.scrollLeft,pageY:n.top+s-this.scrollTop}},this.visualizeFocus=function(){i.addCssClass(this.container,"ace_focus")},this.visualizeBlur=function(){i.removeCssClass(this.container,"ace_focus")},this.showComposition=function(e){this.$composition=e,e.cssText||(e.cssText=this.textarea.style.cssText),e.useTextareaForIME=this.$useTextareaForIME,this.$useTextareaForIME?(i.addCssClass(this.textarea,"ace_composition"),this.textarea.style.cssText="",this.$moveTextAreaToCursor(),this.$cursorLayer.element.style.display="none"):e.markerId=this.session.addMarker(e.markerRange,"ace_composition_marker","text")},this.setCompositionText=function(e){var t=this.session.selection.cursor;this.addToken(e,"composition_placeholder",t.row,t.column),this.$moveTextAreaToCursor()},this.hideComposition=function(){if(!this.$composition)return;this.$composition.markerId&&this.session.removeMarker(this.$composition.markerId),i.removeCssClass(this.textarea,"ace_composition"),this.textarea.style.cssText=this.$composition.cssText,this.$composition=null,this.$cursorLayer.element.style.display=""},this.addToken=function(e,t,n,r){var i=this.session;i.bgTokenizer.lines[n]=null;var s={type:t,value:e},o=i.getTokens(n);if(r==null)o.push(s);else{var u=0;for(var a=0;a50&&e.length>this.$doc.getLength()>>1?this.call("setValue",[this.$doc.getValue()]):this.emit("change",{data:e})}}).call(f.prototype);var l=function(e,t,n){var r=null,i=!1,u=Object.create(s),a=[],l=new f({messageBuffer:a,terminate:function(){},postMessage:function(e){a.push(e);if(!r)return;i?setTimeout(c):c()}});l.setEmitSync=function(e){i=e};var c=function(){var e=a.shift();e.command?r[e.command].apply(r,e.args):e.event&&u._signal(e.event,e.data)};return u.postMessage=function(e){l.onMessage({data:e})},u.callback=function(e,t){this.postMessage({type:"call",id:t,data:e})},u.emit=function(e,t){this.postMessage({type:"event",name:e,data:t})},o.loadModule(["worker",t],function(e){r=new e[n](u);while(a.length)c()}),l};t.UIWorkerClient=l,t.WorkerClient=f,t.createWorker=a}),ace.define("ace/placeholder",["require","exports","module","ace/range","ace/lib/event_emitter","ace/lib/oop"],function(e,t,n){"use strict";var r=e("./range").Range,i=e("./lib/event_emitter").EventEmitter,s=e("./lib/oop"),o=function(e,t,n,r,i,s){var o=this;this.length=t,this.session=e,this.doc=e.getDocument(),this.mainClass=i,this.othersClass=s,this.$onUpdate=this.onUpdate.bind(this),this.doc.on("change",this.$onUpdate),this.$others=r,this.$onCursorChange=function(){setTimeout(function(){o.onCursorChange()})},this.$pos=n;var u=e.getUndoManager().$undoStack||e.getUndoManager().$undostack||{length:-1};this.$undoStackDepth=u.length,this.setup(),e.selection.on("changeCursor",this.$onCursorChange)};(function(){s.implement(this,i),this.setup=function(){var e=this,t=this.doc,n=this.session;this.selectionBefore=n.selection.toJSON(),n.selection.inMultiSelectMode&&n.selection.toSingleRange(),this.pos=t.createAnchor(this.$pos.row,this.$pos.column);var i=this.pos;i.$insertRight=!0,i.detach(),i.markerId=n.addMarker(new r(i.row,i.column,i.row,i.column+this.length),this.mainClass,null,!1),this.others=[],this.$others.forEach(function(n){var r=t.createAnchor(n.row,n.column);r.$insertRight=!0,r.detach(),e.others.push(r)}),n.setUndoSelect(!1)},this.showOtherMarkers=function(){if(this.othersActive)return;var e=this.session,t=this;this.othersActive=!0,this.others.forEach(function(n){n.markerId=e.addMarker(new r(n.row,n.column,n.row,n.column+t.length),t.othersClass,null,!1)})},this.hideOtherMarkers=function(){if(!this.othersActive)return;this.othersActive=!1;for(var e=0;e=this.pos.column&&t.start.column<=this.pos.column+this.length+1,s=t.start.column-this.pos.column;this.updateAnchors(e),i&&(this.length+=n);if(i&&!this.session.$fromUndo)if(e.action==="insert")for(var o=this.others.length-1;o>=0;o--){var u=this.others[o],a={row:u.row,column:u.column+s};this.doc.insertMergedLines(a,e.lines)}else if(e.action==="remove")for(var o=this.others.length-1;o>=0;o--){var u=this.others[o],a={row:u.row,column:u.column+s};this.doc.remove(new r(a.row,a.column,a.row,a.column-n))}this.$updating=!1,this.updateMarkers()},this.updateAnchors=function(e){this.pos.onChange(e);for(var t=this.others.length;t--;)this.others[t].onChange(e);this.updateMarkers()},this.updateMarkers=function(){if(this.$updating)return;var e=this,t=this.session,n=function(n,i){t.removeMarker(n.markerId),n.markerId=t.addMarker(new r(n.row,n.column,n.row,n.column+e.length),i,null,!1)};n(this.pos,this.mainClass);for(var i=this.others.length;i--;)n(this.others[i],this.othersClass)},this.onCursorChange=function(e){if(this.$updating||!this.session)return;var t=this.session.selection.getCursor();t.row===this.pos.row&&t.column>=this.pos.column&&t.column<=this.pos.column+this.length?(this.showOtherMarkers(),this._emit("cursorEnter",e)):(this.hideOtherMarkers(),this._emit("cursorLeave",e))},this.detach=function(){this.session.removeMarker(this.pos&&this.pos.markerId),this.hideOtherMarkers(),this.doc.removeEventListener("change",this.$onUpdate),this.session.selection.removeEventListener("changeCursor",this.$onCursorChange),this.session.setUndoSelect(!0),this.session=null},this.cancel=function(){if(this.$undoStackDepth===-1)return;var e=this.session.getUndoManager(),t=(e.$undoStack||e.$undostack).length-this.$undoStackDepth;for(var n=0;n1&&!this.inMultiSelectMode&&(this._signal("multiSelect"),this.inMultiSelectMode=!0,this.session.$undoSelect=!1,this.rangeList.attach(this.session)),t||this.fromOrientedRange(e)},this.toSingleRange=function(e){e=e||this.ranges[0];var t=this.rangeList.removeAll();t.length&&this.$onRemoveRange(t),e&&this.fromOrientedRange(e)},this.substractPoint=function(e){var t=this.rangeList.substractPoint(e);if(t)return this.$onRemoveRange(t),t[0]},this.mergeOverlappingRanges=function(){var e=this.rangeList.merge();e.length&&this.$onRemoveRange(e)},this.$onAddRange=function(e){this.rangeCount=this.rangeList.ranges.length,this.ranges.unshift(e),this._signal("addRange",{range:e})},this.$onRemoveRange=function(e){this.rangeCount=this.rangeList.ranges.length;if(this.rangeCount==1&&this.inMultiSelectMode){var t=this.rangeList.ranges.pop();e.push(t),this.rangeCount=0}for(var n=e.length;n--;){var r=this.ranges.indexOf(e[n]);this.ranges.splice(r,1)}this._signal("removeRange",{ranges:e}),this.rangeCount===0&&this.inMultiSelectMode&&(this.inMultiSelectMode=!1,this._signal("singleSelect"),this.session.$undoSelect=!0,this.rangeList.detach(this.session)),t=t||this.ranges[0],t&&!t.isEqual(this.getRange())&&this.fromOrientedRange(t)},this.$initRangeList=function(){if(this.rangeList)return;this.rangeList=new r,this.ranges=[],this.rangeCount=0},this.getAllRanges=function(){return this.rangeCount?this.rangeList.ranges.concat():[this.getRange()]},this.splitIntoLines=function(){if(this.rangeCount>1){var e=this.rangeList.ranges,t=e[e.length-1],n=i.fromPoints(e[0].start,t.end);this.toSingleRange(),this.setSelectionRange(n,t.cursor==t.start)}else{var n=this.getRange(),r=this.isBackwards(),s=n.start.row,o=n.end.row;if(s==o){if(r)var u=n.end,a=n.start;else var u=n.start,a=n.end;this.addRange(i.fromPoints(a,a)),this.addRange(i.fromPoints(u,u));return}var f=[],l=this.getLineRange(s,!0);l.start.column=n.start.column,f.push(l);for(var c=s+1;c1){var e=this.rangeList.ranges,t=e[e.length-1],n=i.fromPoints(e[0].start,t.end);this.toSingleRange(),this.setSelectionRange(n,t.cursor==t.start)}else{var r=this.session.documentToScreenPosition(this.cursor),s=this.session.documentToScreenPosition(this.anchor),o=this.rectangularRangeBlock(r,s);o.forEach(this.addRange,this)}},this.rectangularRangeBlock=function(e,t,n){var r=[],s=e.column0)g--;if(g>0){var y=0;while(r[y].isEmpty())y++}for(var b=g;b>=y;b--)r[b].isEmpty()&&r.splice(b,1)}return r}}.call(s.prototype);var d=e("./editor").Editor;(function(){this.updateSelectionMarkers=function(){this.renderer.updateCursor(),this.renderer.updateBackMarkers()},this.addSelectionMarker=function(e){e.cursor||(e.cursor=e.end);var t=this.getSelectionStyle();return e.marker=this.session.addMarker(e,"ace_selection",t),this.session.$selectionMarkers.push(e),this.session.selectionMarkerCount=this.session.$selectionMarkers.length,e},this.removeSelectionMarker=function(e){if(!e.marker)return;this.session.removeMarker(e.marker);var t=this.session.$selectionMarkers.indexOf(e);t!=-1&&this.session.$selectionMarkers.splice(t,1),this.session.selectionMarkerCount=this.session.$selectionMarkers.length},this.removeSelectionMarkers=function(e){var t=this.session.$selectionMarkers;for(var n=e.length;n--;){var r=e[n];if(!r.marker)continue;this.session.removeMarker(r.marker);var i=t.indexOf(r);i!=-1&&t.splice(i,1)}this.session.selectionMarkerCount=t.length},this.$onAddRange=function(e){this.addSelectionMarker(e.range),this.renderer.updateCursor(),this.renderer.updateBackMarkers()},this.$onRemoveRange=function(e){this.removeSelectionMarkers(e.ranges),this.renderer.updateCursor(),this.renderer.updateBackMarkers()},this.$onMultiSelect=function(e){if(this.inMultiSelectMode)return;this.inMultiSelectMode=!0,this.setStyle("ace_multiselect"),this.keyBinding.addKeyboardHandler(f.keyboardHandler),this.commands.setDefaultHandler("exec",this.$onMultiSelectExec),this.renderer.updateCursor(),this.renderer.updateBackMarkers()},this.$onSingleSelect=function(e){if(this.session.multiSelect.inVirtualMode)return;this.inMultiSelectMode=!1,this.unsetStyle("ace_multiselect"),this.keyBinding.removeKeyboardHandler(f.keyboardHandler),this.commands.removeDefaultHandler("exec",this.$onMultiSelectExec),this.renderer.updateCursor(),this.renderer.updateBackMarkers(),this._emit("changeSelection")},this.$onMultiSelectExec=function(e){var t=e.command,n=e.editor;if(!n.multiSelect)return;if(!t.multiSelectAction){var r=t.exec(n,e.args||{});n.multiSelect.addRange(n.multiSelect.toOrientedRange()),n.multiSelect.mergeOverlappingRanges()}else t.multiSelectAction=="forEach"?r=n.forEachSelection(t,e.args):t.multiSelectAction=="forEachLine"?r=n.forEachSelection(t,e.args,!0):t.multiSelectAction=="single"?(n.exitMultiSelectMode(),r=t.exec(n,e.args||{})):r=t.multiSelectAction(n,e.args||{});return r},this.forEachSelection=function(e,t,n){if(this.inVirtualSelectionMode)return;var r=n&&n.keepOrder,i=n==1||n&&n.$byLines,o=this.session,u=this.selection,a=u.rangeList,f=(r?u:a).ranges,l;if(!f.length)return e.exec?e.exec(this,t||{}):e(this,t||{});var c=u._eventRegistry;u._eventRegistry={};var h=new s(o);this.inVirtualSelectionMode=!0;for(var p=f.length;p--;){if(i)while(p>0&&f[p].start.row==f[p-1].end.row)p--;h.fromOrientedRange(f[p]),h.index=p,this.selection=o.selection=h;var d=e.exec?e.exec(this,t||{}):e(this,t||{});!l&&d!==undefined&&(l=d),h.toOrientedRange(f[p])}h.detach(),this.selection=o.selection=u,this.inVirtualSelectionMode=!1,u._eventRegistry=c,u.mergeOverlappingRanges(),u.ranges[0]&&u.fromOrientedRange(u.ranges[0]);var v=this.renderer.$scrollAnimation;return this.onCursorChange(),this.onSelectionChange(),v&&v.from==v.to&&this.renderer.animateScrolling(v.from),l},this.exitMultiSelectMode=function(){if(!this.inMultiSelectMode||this.inVirtualSelectionMode)return;this.multiSelect.toSingleRange()},this.getSelectedText=function(){var e="";if(this.inMultiSelectMode&&!this.inVirtualSelectionMode){var t=this.multiSelect.rangeList.ranges,n=[];for(var r=0;r0);u<0&&(u=0),f>=c&&(f=c-1)}var p=this.session.removeFullLines(u,f);p=this.$reAlignText(p,l),this.session.insert({row:u,column:0},p.join("\n")+"\n"),l||(o.start.column=0,o.end.column=p[p.length-1].length),this.selection.setRange(o)}else{s.forEach(function(e){t.substractPoint(e.cursor)});var d=0,v=Infinity,m=n.map(function(t){var n=t.cursor,r=e.getLine(n.row),i=r.substr(n.column).search(/\S/g);return i==-1&&(i=0),n.column>d&&(d=n.column),io?e.insert(r,a.stringRepeat(" ",s-o)):e.remove(new i(r.row,r.column,r.row,r.column-s+o)),t.start.column=t.end.column=d,t.start.row=t.end.row=r.row,t.cursor=t.end}),t.fromOrientedRange(n[0]),this.renderer.updateCursor(),this.renderer.updateBackMarkers()}},this.$reAlignText=function(e,t){function u(e){return a.stringRepeat(" ",e)}function f(e){return e[2]?u(i)+e[2]+u(s-e[2].length+o)+e[4].replace(/^([=:])\s+/,"$1 "):e[0]}function l(e){return e[2]?u(i+s-e[2].length)+e[2]+u(o)+e[4].replace(/^([=:])\s+/,"$1 "):e[0]}function c(e){return e[2]?u(i)+e[2]+u(o)+e[4].replace(/^([=:])\s+/,"$1 "):e[0]}var n=!0,r=!0,i,s,o;return e.map(function(e){var t=e.match(/(\s*)(.*?)(\s*)([=:].*)/);return t?i==null?(i=t[1].length,s=t[2].length,o=t[3].length,t):(i+s+o!=t[1].length+t[2].length+t[3].length&&(r=!1),i!=t[1].length&&(n=!1),i>t[1].length&&(i=t[1].length),st[3].length&&(o=t[3].length),t):[e]}).map(t?f:n?r?l:f:c)}}).call(d.prototype),t.onSessionChange=function(e){var t=e.session;t&&!t.multiSelect&&(t.$selectionMarkers=[],t.selection.$initRangeList(),t.multiSelect=t.selection),this.multiSelect=t&&t.multiSelect;var n=e.oldSession;n&&(n.multiSelect.off("addRange",this.$onAddRange),n.multiSelect.off("removeRange",this.$onRemoveRange),n.multiSelect.off("multiSelect",this.$onMultiSelect),n.multiSelect.off("singleSelect",this.$onSingleSelect),n.multiSelect.lead.off("change",this.$checkMultiselectChange),n.multiSelect.anchor.off("change",this.$checkMultiselectChange)),t&&(t.multiSelect.on("addRange",this.$onAddRange),t.multiSelect.on("removeRange",this.$onRemoveRange),t.multiSelect.on("multiSelect",this.$onMultiSelect),t.multiSelect.on("singleSelect",this.$onSingleSelect),t.multiSelect.lead.on("change",this.$checkMultiselectChange),t.multiSelect.anchor.on("change",this.$checkMultiselectChange)),t&&this.inMultiSelectMode!=t.selection.inMultiSelectMode&&(t.selection.inMultiSelectMode?this.$onMultiSelect():this.$onSingleSelect())},t.MultiSelect=m,e("./config").defineOptions(d.prototype,"editor",{enableMultiselect:{set:function(e){m(this),e?(this.on("changeSession",this.$multiselectOnSessionChange),this.on("mousedown",o)):(this.off("changeSession",this.$multiselectOnSessionChange),this.off("mousedown",o))},value:!0},enableBlockSelect:{set:function(e){this.$blockSelectEnabled=e},value:!0}})}),ace.define("ace/mode/folding/fold_mode",["require","exports","module","ace/range"],function(e,t,n){"use strict";var r=e("../../range").Range,i=t.FoldMode=function(){};(function(){this.foldingStartMarker=null,this.foldingStopMarker=null,this.getFoldWidget=function(e,t,n){var r=e.getLine(n);return this.foldingStartMarker.test(r)?"start":t=="markbeginend"&&this.foldingStopMarker&&this.foldingStopMarker.test(r)?"end":""},this.getFoldWidgetRange=function(e,t,n){return null},this.indentationBlock=function(e,t,n){var i=/\S/,s=e.getLine(t),o=s.search(i);if(o==-1)return;var u=n||s.length,a=e.getLength(),f=t,l=t;while(++tf){var h=e.getLine(l).length;return new r(f,u,l,h)}},this.openingBracketBlock=function(e,t,n,i,s){var o={row:n,column:i+1},u=e.$findClosingBracket(t,o,s);if(!u)return;var a=e.foldWidgets[u.row];return a==null&&(a=e.getFoldWidget(u.row)),a=="start"&&u.row>o.row&&(u.row--,u.column=e.getLine(u.row).length),r.fromPoints(o,u)},this.closingBracketBlock=function(e,t,n,i,s){var o={row:n,column:i},u=e.$findOpeningBracket(t,o);if(!u)return;return u.column++,o.column--,r.fromPoints(u,o)}}).call(i.prototype)}),ace.define("ace/theme/textmate",["require","exports","module","ace/lib/dom"],function(e,t,n){"use strict";t.isDark=!1,t.cssClass="ace-tm",t.cssText='.ace-tm .ace_gutter {background: #f0f0f0;color: #333;}.ace-tm .ace_print-margin {width: 1px;background: #e8e8e8;}.ace-tm .ace_fold {background-color: #6B72E6;}.ace-tm {background-color: #FFFFFF;color: black;}.ace-tm .ace_cursor {color: black;}.ace-tm .ace_invisible {color: rgb(191, 191, 191);}.ace-tm .ace_storage,.ace-tm .ace_keyword {color: blue;}.ace-tm .ace_constant {color: rgb(197, 6, 11);}.ace-tm .ace_constant.ace_buildin {color: rgb(88, 72, 246);}.ace-tm .ace_constant.ace_language {color: rgb(88, 92, 246);}.ace-tm .ace_constant.ace_library {color: rgb(6, 150, 14);}.ace-tm .ace_invalid {background-color: rgba(255, 0, 0, 0.1);color: red;}.ace-tm .ace_support.ace_function {color: rgb(60, 76, 114);}.ace-tm .ace_support.ace_constant {color: rgb(6, 150, 14);}.ace-tm .ace_support.ace_type,.ace-tm .ace_support.ace_class {color: rgb(109, 121, 222);}.ace-tm .ace_keyword.ace_operator {color: rgb(104, 118, 135);}.ace-tm .ace_string {color: rgb(3, 106, 7);}.ace-tm .ace_comment {color: rgb(76, 136, 107);}.ace-tm .ace_comment.ace_doc {color: rgb(0, 102, 255);}.ace-tm .ace_comment.ace_doc.ace_tag {color: rgb(128, 159, 191);}.ace-tm .ace_constant.ace_numeric {color: rgb(0, 0, 205);}.ace-tm .ace_variable {color: rgb(49, 132, 149);}.ace-tm .ace_xml-pe {color: rgb(104, 104, 91);}.ace-tm .ace_entity.ace_name.ace_function {color: #0000A2;}.ace-tm .ace_heading {color: rgb(12, 7, 255);}.ace-tm .ace_list {color:rgb(185, 6, 144);}.ace-tm .ace_meta.ace_tag {color:rgb(0, 22, 142);}.ace-tm .ace_string.ace_regex {color: rgb(255, 0, 0)}.ace-tm .ace_marker-layer .ace_selection {background: rgb(181, 213, 255);}.ace-tm.ace_multiselect .ace_selection.ace_start {box-shadow: 0 0 3px 0px white;}.ace-tm .ace_marker-layer .ace_step {background: rgb(252, 255, 0);}.ace-tm .ace_marker-layer .ace_stack {background: rgb(164, 229, 101);}.ace-tm .ace_marker-layer .ace_bracket {margin: -1px 0 0 -1px;border: 1px solid rgb(192, 192, 192);}.ace-tm .ace_marker-layer .ace_active-line {background: rgba(0, 0, 0, 0.07);}.ace-tm .ace_gutter-active-line {background-color : #dcdcdc;}.ace-tm .ace_marker-layer .ace_selected-word {background: rgb(250, 250, 255);border: 1px solid rgb(200, 200, 250);}.ace-tm .ace_indent-guide {background: url("data:image/png;base64,iVBORw0KGgoAAAANSUhEUgAAAAEAAAACCAYAAACZgbYnAAAAE0lEQVQImWP4////f4bLly//BwAmVgd1/w11/gAAAABJRU5ErkJggg==") right repeat-y;}',t.$id="ace/theme/textmate";var r=e("../lib/dom");r.importCssString(t.cssText,t.cssClass)}),ace.define("ace/line_widgets",["require","exports","module","ace/lib/oop","ace/lib/dom","ace/range"],function(e,t,n){"use strict";function o(e){this.session=e,this.session.widgetManager=this,this.session.getRowLength=this.getRowLength,this.session.$getWidgetScreenLength=this.$getWidgetScreenLength,this.updateOnChange=this.updateOnChange.bind(this),this.renderWidgets=this.renderWidgets.bind(this),this.measureWidgets=this.measureWidgets.bind(this),this.session._changedWidgets=[],this.$onChangeEditor=this.$onChangeEditor.bind(this),this.session.on("change",this.updateOnChange),this.session.on("changeFold",this.updateOnFold),this.session.on("changeEditor",this.$onChangeEditor)}var r=e("./lib/oop"),i=e("./lib/dom"),s=e("./range").Range;(function(){this.getRowLength=function(e){var t;return this.lineWidgets?t=this.lineWidgets[e]&&this.lineWidgets[e].rowCount||0:t=0,!this.$useWrapMode||!this.$wrapData[e]?1+t:this.$wrapData[e].length+1+t},this.$getWidgetScreenLength=function(){var e=0;return this.lineWidgets.forEach(function(t){t&&t.rowCount&&!t.hidden&&(e+=t.rowCount)}),e},this.$onChangeEditor=function(e){this.attach(e.editor)},this.attach=function(e){e&&e.widgetManager&&e.widgetManager!=this&&e.widgetManager.detach();if(this.editor==e)return;this.detach(),this.editor=e,e&&(e.widgetManager=this,e.renderer.on("beforeRender",this.measureWidgets),e.renderer.on("afterRender",this.renderWidgets))},this.detach=function(e){var t=this.editor;if(!t)return;this.editor=null,t.widgetManager=null,t.renderer.off("beforeRender",this.measureWidgets),t.renderer.off("afterRender",this.renderWidgets);var n=this.session.lineWidgets;n&&n.forEach(function(e){e&&e.el&&e.el.parentNode&&(e._inDocument=!1,e.el.parentNode.removeChild(e.el))})},this.updateOnFold=function(e,t){var n=t.lineWidgets;if(!n||!e.action)return;var r=e.data,i=r.start.row,s=r.end.row,o=e.action=="add";for(var u=i+1;u0&&!r[i])i--;this.firstRow=n.firstRow,this.lastRow=n.lastRow,t.$cursorLayer.config=n;for(var o=i;o<=s;o++){var u=r[o];if(!u||!u.el)continue;if(u.hidden){u.el.style.top=-100-(u.pixelHeight||0)+"px";continue}u._inDocument||(u._inDocument=!0,t.container.appendChild(u.el));var a=t.$cursorLayer.getPixelPosition({row:o,column:0},!0).top;u.coverLine||(a+=n.lineHeight*this.session.getRowLineCount(u.row)),u.el.style.top=a-n.offset+"px";var f=u.coverGutter?0:t.gutterWidth;u.fixedWidth||(f-=t.scrollLeft),u.el.style.left=f+"px",u.fullWidth&&u.screenWidth&&(u.el.style.minWidth=n.width+2*n.padding+"px"),u.fixedWidth?u.el.style.right=t.scrollBar.getWidth()+"px":u.el.style.right=""}}}).call(o.prototype),t.LineWidgets=o}),ace.define("ace/ext/error_marker",["require","exports","module","ace/line_widgets","ace/lib/dom","ace/range"],function(e,t,n){"use strict";function o(e,t,n){var r=0,i=e.length-1;while(r<=i){var s=r+i>>1,o=n(t,e[s]);if(o>0)r=s+1;else{if(!(o<0))return s;i=s-1}}return-(r+1)}function u(e,t,n){var r=e.getAnnotations().sort(s.comparePoints);if(!r.length)return;var i=o(r,{row:t,column:-1},s.comparePoints);i<0&&(i=-i-1),i>=r.length?i=n>0?0:r.length-1:i===0&&n<0&&(i=r.length-1);var u=r[i];if(!u||!n)return;if(u.row===t){do u=r[i+=n];while(u&&u.row===t);if(!u)return r.slice()}var a=[];t=u.row;do a[n<0?"unshift":"push"](u),u=r[i+=n];while(u&&u.row==t);return a.length&&a}var r=e("../line_widgets").LineWidgets,i=e("../lib/dom"),s=e("../range").Range;t.showErrorMarker=function(e,t){var n=e.session;n.widgetManager||(n.widgetManager=new r(n),n.widgetManager.attach(e));var s=e.getCursorPosition(),o=s.row,a=n.widgetManager.getWidgetsAtRow(o).filter(function(e){return e.type=="errorMarker"})[0];a?a.destroy():o-=t;var f=u(n,o,t),l;if(f){var c=f[0];s.column=(c.pos&&typeof c.column!="number"?c.pos.sc:c.column)||0,s.row=c.row,l=e.renderer.$gutterLayer.$annotations[s.row]}else{if(a)return;l={text:["Looks good!"],className:"ace_ok"}}e.session.unfold(s.row),e.selection.moveToPosition(s);var h={row:s.row,fixedWidth:!0,coverGutter:!0,el:i.createElement("div"),type:"errorMarker"},p=h.el.appendChild(i.createElement("div")),d=h.el.appendChild(i.createElement("div"));d.className="error_widget_arrow "+l.className;var v=e.renderer.$cursorLayer.getPixelPosition(s).left;d.style.left=v+e.renderer.gutterWidth-5+"px",h.el.className="error_widget_wrapper",p.className="error_widget "+l.className,p.innerHTML=l.text.join("
"),p.appendChild(i.createElement("div"));var m=function(e,t,n){if(t===0&&(n==="esc"||n==="return"))return h.destroy(),{command:"null"}};h.destroy=function(){if(e.$mouseHandler.isMousePressed)return;e.keyBinding.removeKeyboardHandler(m),n.widgetManager.removeLineWidget(h),e.off("changeSelection",h.destroy),e.off("changeSession",h.destroy),e.off("mouseup",h.destroy),e.off("change",h.destroy)},e.keyBinding.addKeyboardHandler(m),e.on("changeSelection",h.destroy),e.on("changeSession",h.destroy),e.on("mouseup",h.destroy),e.on("change",h.destroy),e.session.widgetManager.addLineWidget(h),h.el.onmousedown=e.focus.bind(e),e.renderer.scrollCursorIntoView(null,.5,{bottom:h.el.offsetHeight})},i.importCssString(" .error_widget_wrapper { background: inherit; color: inherit; border:none } .error_widget { border-top: solid 2px; border-bottom: solid 2px; margin: 5px 0; padding: 10px 40px; white-space: pre-wrap; } .error_widget.ace_error, .error_widget_arrow.ace_error{ border-color: #ff5a5a } .error_widget.ace_warning, .error_widget_arrow.ace_warning{ border-color: #F1D817 } .error_widget.ace_info, .error_widget_arrow.ace_info{ border-color: #5a5a5a } .error_widget.ace_ok, .error_widget_arrow.ace_ok{ border-color: #5aaa5a } .error_widget_arrow { position: absolute; border: solid 5px; border-top-color: transparent!important; border-right-color: transparent!important; border-left-color: transparent!important; top: -5px; }","")}),ace.define("ace/ace",["require","exports","module","ace/lib/fixoldbrowsers","ace/lib/dom","ace/lib/event","ace/range","ace/editor","ace/edit_session","ace/undomanager","ace/virtual_renderer","ace/worker/worker_client","ace/keyboard/hash_handler","ace/placeholder","ace/multi_select","ace/mode/folding/fold_mode","ace/theme/textmate","ace/ext/error_marker","ace/config"],function(e,t,n){"use strict";e("./lib/fixoldbrowsers");var r=e("./lib/dom"),i=e("./lib/event"),s=e("./range").Range,o=e("./editor").Editor,u=e("./edit_session").EditSession,a=e("./undomanager").UndoManager,f=e("./virtual_renderer").VirtualRenderer;e("./worker/worker_client"),e("./keyboard/hash_handler"),e("./placeholder"),e("./multi_select"),e("./mode/folding/fold_mode"),e("./theme/textmate"),e("./ext/error_marker"),t.config=e("./config"),t.require=e,typeof define=="function"&&(t.define=define),t.edit=function(e,n){if(typeof e=="string"){var s=e;e=document.getElementById(s);if(!e)throw new Error("ace.edit can't find div #"+s)}if(e&&e.env&&e.env.editor instanceof o)return e.env.editor;var u="";if(e&&/input|textarea/i.test(e.tagName)){var a=e;u=a.value,e=r.createElement("pre"),a.parentNode.replaceChild(e,a)}else e&&(u=e.textContent,e.innerHTML="");var l=t.createEditSession(u),c=new o(new f(e),l,n),h={document:l,editor:c,onResize:c.resize.bind(c,null)};return a&&(h.textarea=a),i.addListener(window,"resize",h.onResize),c.on("destroy",function(){i.removeListener(window,"resize",h.onResize),h.editor.container.env=null}),c.container.env=c.env=h,c},t.createEditSession=function(e,t){var n=new u(e,t);return n.setUndoManager(new a),n},t.Range=s,t.Editor=o,t.EditSession=u,t.UndoManager=a,t.VirtualRenderer=f,t.version=t.config.version}); (function() { + ace.require(["ace/ace"], function(a) { + if (a) { + a.config.init(true); + a.define = ace.define; + } + if (!window.ace) + window.ace = a; + for (var key in a) if (a.hasOwnProperty(key)) + window.ace[key] = a[key]; + window.ace["default"] = window.ace; + if (typeof module == "object" && typeof exports == "object" && module) { + module.exports = window.ace; + } + }); + })(); diff --git a/static/scripts/archive/frontpage.js b/static/scripts/archive/frontpage.js new file mode 100644 index 00000000..d3371155 --- /dev/null +++ b/static/scripts/archive/frontpage.js @@ -0,0 +1,230 @@ +//checkForGCodeUpdate(); + +//setInterval(function(){ alert("Hello"); }, 3000); + +var scale = 1; +var startWidth = 0.1 +var draw = SVG('workarea').size('100%','100%').panZoom({zoomMin: 1, zoomMax: 500, zoomFactor:2.5}); +var viewbox = draw.viewbox(); +var originX = viewbox.width/2; +var originY = viewbox.height/2; +var currentPosX = 0; +var currentPosY = 0; +var gcode = null; +//var rect = draw.rect(100,100).attr({fill: '#f06'}) +//var sheet = draw.image('/static/images/materials/Plywood_texture.JPG',96,48).center(originX,originY) + +var gridLines = draw.group() +gridLines.add(draw.line(0*scale,0*scale,96*scale,0*scale).stroke({width:startWidth, color: '#000'})) +gridLines.add(draw.line(0*scale,48*scale,96*scale,48*scale).stroke({width:startWidth, color: '#000'})) +gridLines.add(draw.line(0*scale,24*scale,96*scale,24*scale).stroke({width:startWidth, color: '#000'})) +gridLines.add(draw.line(0*scale,0*scale,0*scale,48*scale).stroke({width:startWidth, color: '#000'})) +gridLines.add(draw.line(24*scale,0*scale,24*scale,48*scale).stroke({width:startWidth, color: '#000'})) +gridLines.add(draw.line(48*scale,0*scale,48*scale,48*scale).stroke({width:startWidth, color: '#000'})) +gridLines.add(draw.line(72*scale,0*scale,72*scale,48*scale).stroke({width:startWidth, color: '#000'})) +gridLines.add(draw.line(96*scale,0*scale,96*scale,48*scale).stroke({width:startWidth, color: '#000'})) +gridLines.center(originX,originY) +//gridLines.scale(scale,scale) + +var sled = draw.group() +sled.add(draw.line(1.5*scale,-0.0*scale,1.5*scale,3.0*scale).stroke({width:startWidth,color:"#F00"})) +sled.add(draw.line(-0.0*scale,1.5*scale,3.0*scale,1.5*scale).stroke({width:startWidth,color:"#F00"})) +sled.add(draw.circle(3*scale).stroke({width:startWidth,color:"#F00"}).fill({color:"#fff",opacity:0})) +sled.center(originX,originY) + +var home = draw.group() +home.add(draw.line(0.75*scale,-0.0*scale,0.75*scale,1.5*scale).stroke({width:startWidth,color:"#0F0"})) +home.add(draw.line(-0.0*scale,0.75*scale,1.5*scale,0.75*scale).stroke({width:startWidth,color:"#0F0"})) +home.add(draw.circle(1.5*scale).stroke({width:startWidth,color:"#0F0"}).fill({color:"#fff",opacity:0})) +home.center(originX,originY) +/ + +draw.zoom(10, {x:originX,y:originY}); +var startZoom = draw.zoom(); + +draw.on('pinchZoomEnd', function(ev){ + setTimeout(rescale,0.01) +}) + +draw.on('zoom', function(box, focus){ + setTimeout(rescale,0.01) +}) + +function rescale(){ + width = startWidth*startZoom/draw.zoom(); + draw.each(function(_i, _children){ + this.each(function(i,children){ + this.attr({'stroke-width':width}); + }) + }) +} + +function positionUpdate(x,y,z){ + var _x, _y =0 + if ($("#units").text()=="MM"){ + _x = originX+x*scale/25.4 + _y = originY-y*scale/25.4 + _z = z*scale/25.4/2*360 + } + else{ + _x = originX+x*scale; + _y = originY-y*scale + _z = z*scale/2*360 + } + sled.front() + sled.center(_x, _y) +} + + +function homePositionUpdate(x,y){ + var _x, _y =0 + //console.log(x) + if ($("#units").text()=="MM"){ + _x = originX+x*scale/25.4 + _y = originY-y*scale/25.4 + } + else{ + _x = originX+x*scale; + _y = originY-y*scale + } + home.center(_x, _y); +} + +function unitSwitch(){ + if ( $("#units").text()=="MM") { + $("#units").text("INCHES"); + distToMove = Math.round($("#distToMove").val()/25.4,3) + $("#distToMove").val(distToMove); + updateSetting('toInches',distToMove); + } else { + $("#units").text("MM"); + distToMove = Math.round($("#distToMove").val()*25.4,3) + $("#distToMove").val(distToMove); + updateSetting('toMM',distToMove); + } +} + +$(document).ready(function(){ + settingRequest("Computed Settings","units"); + settingRequest("Computed Settings","distToMove"); + settingRequest("Computed Settings","homePosition"); + checkForGCodeUpdate(); + var controllerMessage = document.getElementById('controllerMessage'); + controllerMessage.scrollTop = controllerMessage.scrollHeight; + //var $controllerMessage = $("#controllerMessage"); + //$controllerMessage.scrollTop($controllerMessage[0].scrollHeight); +}); + +function pauseRun(){ + if ($("#pauseButton").text()=="Pause"){ + action('pauseRun'); + } + else { + action('resumeRun'); + } +} + +function processRequestedSetting(msg){ + console.log(msg); + if (msg.setting=="pauseButtonSetting"){ + if(msg.value=="Resume") + $('#pauseButton').removeClass('btn-warning').addClass('btn-info'); + else + $('#pauseButton').removeClass('btn-info').addClass('btn-warning'); + $("#pauseButton").text(msg.value); + } + if (msg.setting=="units"){ + console.log("requestedSetting:"+msg.value); + $("#units").text(msg.value) + } + if (msg.setting=="distToMove"){ + console.log("requestedSetting for distToMove:"+msg.value); + $("#distToMove").val(msg.value) + } + if ((msg.setting=="unitsZ") || (msg.setting=="distToMoveZ")){ + if (typeof processZAxisRequestedSetting === "function") { + processZAxisRequestedSetting(msg) + } + } +} + +function processPositionMessage(msg){ + var _json = JSON.parse(msg.data); + $('#positionMessage').html('XPos:'+parseFloat(_json.xval).toFixed(2)+' Ypos:'+parseFloat(_json.yval).toFixed(2)+' ZPos:'+parseFloat(_json.zval).toFixed(2)); + $('#percentComplete').html(_json.pcom) + positionUpdate(_json.xval,_json.yval,_json.zval); +} + +function processHomePositionMessage(msg){ + var _json = JSON.parse(msg.data); + console.log(_json.xval) + $('#homePositionMessage').html('XPos:'+parseFloat(_json.xval).toFixed(2)+' Ypos:'+parseFloat(_json.yval).toFixed(2)); + homePositionUpdate(_json.xval,_json.yval); +} + +function gcodeUpdate(msg){ + console.log("updating gcode"); + if (gcode!=null) { + //console.log("removing gcode"); + gcode.remove(); + } + width = startWidth*startZoom/draw.zoom(); + gcode = draw.group(); + var data = JSON.parse(msg.data) + data.forEach(function(line) { + //console.log(line) + if (line.type=='line'){ + if (line.dashed==true) { + gcode.add(draw.polyline(line.points).fill('none').stroke({width:width, color: '#AA0'})) + } else { + gcode.add(draw.polyline(line.points).fill('none').stroke({width:width, color: '#00F'})) + } + } + gcode.move(originX,originY) + }); +} + +function gcodeUpdateCompressed(msg){ + console.log("updating gcode compressed"); + if (gcode!=null) { + //console.log("removing gcode"); + gcode.remove(); + } + width = startWidth*startZoom/draw.zoom(); + gcode = draw.group(); + //console.log(msg.data); + if (msg.data!=null){ + var uncompressed = pako.inflate(msg.data); + var _str = ab2str(uncompressed); + //var _str = new TextDecoder("utf-8").decode(uncompressed); + //console.log(_str); + var data = JSON.parse(_str) + data.forEach(function(line) { + //console.log(line) + if (line.type=='line'){ + if (line.dashed==true) { + gcode.add(draw.polyline(line.points).fill('none').stroke({width:width, color: '#AA0'})) + } else { + gcode.add(draw.polyline(line.points).fill('none').stroke({width:width, color: '#00F'})) + } + } + gcode.move(originX,originY) + }); + } + $("#fpCircle").hide(); +} + +function ab2str(buf) { + var bufView = new Uint16Array(buf); + var unis ="" + for (var i = 0; i < bufView.length; i++) { + unis=unis+String.fromCharCode(bufView[i]); + } + return unis +} + +function showFPSpinner(msg){ + $("#fpCircle").show(); +} + + diff --git a/static/scripts/svg.js b/static/scripts/archive/svg.js similarity index 100% rename from static/scripts/svg.js rename to static/scripts/archive/svg.js diff --git a/static/scripts/svg.panzoom.min.js b/static/scripts/archive/svg.panzoom.min.js similarity index 100% rename from static/scripts/svg.panzoom.min.js rename to static/scripts/archive/svg.panzoom.min.js diff --git a/static/scripts/base.js b/static/scripts/base.js new file mode 100644 index 00000000..4964cbbc --- /dev/null +++ b/static/scripts/base.js @@ -0,0 +1,256 @@ + +var isMobile = false; //initialize as false +$('.disabler').prop('disabled', true); +var isDisabled = true; + +if(/(android|bb\d+|meego).+mobile|avantgo|bada\/|blackberry|blazer|compal|elaine|fennec|hiptop|iemobile|ip(hone|od)|ipad|iris|kindle|Android|Silk|lge |maemo|midp|mmp|netfront|opera m(ob|in)i|palm( os)?|phone|p(ixi|re)\/|plucker|pocket|psp|series(4|6)0|symbian|treo|up\.(browser|link)|vodafone|wap|windows (ce|phone)|xda|xiino/i.test(navigator.userAgent) + || /1207|6310|6590|3gso|4thp|50[1-6]i|770s|802s|a wa|abac|ac(er|oo|s\-)|ai(ko|rn)|al(av|ca|co)|amoi|an(ex|ny|yw)|aptu|ar(ch|go)|as(te|us)|attw|au(di|\-m|r |s )|avan|be(ck|ll|nq)|bi(lb|rd)|bl(ac|az)|br(e|v)w|bumb|bw\-(n|u)|c55\/|capi|ccwa|cdm\-|cell|chtm|cldc|cmd\-|co(mp|nd)|craw|da(it|ll|ng)|dbte|dc\-s|devi|dica|dmob|do(c|p)o|ds(12|\-d)|el(49|ai)|em(l2|ul)|er(ic|k0)|esl8|ez([4-7]0|os|wa|ze)|fetc|fly(\-|_)|g1 u|g560|gene|gf\-5|g\-mo|go(\.w|od)|gr(ad|un)|haie|hcit|hd\-(m|p|t)|hei\-|hi(pt|ta)|hp( i|ip)|hs\-c|ht(c(\-| |_|a|g|p|s|t)|tp)|hu(aw|tc)|i\-(20|go|ma)|i230|iac( |\-|\/)|ibro|idea|ig01|ikom|im1k|inno|ipaq|iris|ja(t|v)a|jbro|jemu|jigs|kddi|keji|kgt( |\/)|klon|kpt |kwc\-|kyo(c|k)|le(no|xi)|lg( g|\/(k|l|u)|50|54|\-[a-w])|libw|lynx|m1\-w|m3ga|m50\/|ma(te|ui|xo)|mc(01|21|ca)|m\-cr|me(rc|ri)|mi(o8|oa|ts)|mmef|mo(01|02|bi|de|do|t(\-| |o|v)|zz)|mt(50|p1|v )|mwbp|mywa|n10[0-2]|n20[2-3]|n30(0|2)|n50(0|2|5)|n7(0(0|1)|10)|ne((c|m)\-|on|tf|wf|wg|wt)|nok(6|i)|nzph|o2im|op(ti|wv)|oran|owg1|p800|pan(a|d|t)|pdxg|pg(13|\-([1-8]|c))|phil|pire|pl(ay|uc)|pn\-2|po(ck|rt|se)|prox|psio|pt\-g|qa\-a|qc(07|12|21|32|60|\-[2-7]|i\-)|qtek|r380|r600|raks|rim9|ro(ve|zo)|s55\/|sa(ge|ma|mm|ms|ny|va)|sc(01|h\-|oo|p\-)|sdk\/|se(c(\-|0|1)|47|mc|nd|ri)|sgh\-|shar|sie(\-|m)|sk\-0|sl(45|id)|sm(al|ar|b3|it|t5)|so(ft|ny)|sp(01|h\-|v\-|v )|sy(01|mb)|t2(18|50)|t6(00|10|18)|ta(gt|lk)|tcl\-|tdg\-|tel(i|m)|tim\-|t\-mo|to(pl|sh)|ts(70|m\-|m3|m5)|tx\-9|up(\.b|g1|si)|utst|v400|v750|veri|vi(rg|te)|vk(40|5[0-3]|\-v)|vm40|voda|vulc|vx(52|53|60|61|70|80|81|83|85|98)|w3c(\-| )|webc|whit|wi(g |nc|nw)|wmlb|wonu|x700|yas\-|your|zeto|zte\-/i.test(navigator.userAgent.substr(0,4))) { + isMobile = true; +} + +$(document).ready(function(){ + // Make all navbar drop down items collapse the menu when clicked. + if (isMobile) { + $("#navbarSupportedContent a.dropdown-item").attr("data-toggle", "collapse").attr("data-target", "#navbarSupportedContent"); + } +}) + +function processHealthMessage(data){ + //console.log(data.cpuUsage); + $("#cpuUsage").text("CPU: "+Math.round(data.cpuUsage).toString()+"%"); + $("#mobileCPUUsage").text(Math.round(data.cpuUsage).toString()+"%"); + if (data.bufferSize == -1){ + if ($("#bufferSize").is(":hidden") == false){ + $("#bufferSize").hide(); + } + if ((isMobile) && ($("#mobileBufferSize").is(":hidden") == false)){ + $("#mobileBufferSize").hide(); + } + } + else{ + if ($("#bufferSize").is(":hidden") == true){ + $("#bufferSize").show(); + } + if ((isMobile) && ($("#mobileBufferSize").is(":hidden") == true)){ + $("#mobileBufferSize").show(); + } + $("#bufferSize").text("Buffer: "+data.bufferSize.toString()); + $("#mobileBufferSize").text(data.bufferSize.toString()); + } + + +} + +function processControllerStatus(data){ + if (data.status=="disconnected"){ + $("#controllerStatusAlert").text("Not Connected"); + $("#controllerStatusAlert").removeClass('alert-success').addClass('alert-danger'); + $("#mobileControllerStatusAlert").removeClass('alert-success').addClass('alert-danger'); + if (isMobile) + { + $("#mobileControllerStatusAlert").show(); + $("#mobileControllerStatusAlert svg.feather.feather-check-circle").replaceWith(feather.icons["alert-circle"].toSvg()); + } + else + $("#mobileControllerStatusAlert").hide(); + $("#mobileControllerStatusButton").hide(); + + //feather.replace(); + } + else + { + if (data.fakeServoStatus){ + text = data.port+" / Fake Servo ON"; + $("#controllerStatusAlert").hide(); + $("#mobileControllerStatusAlert").hide(); + if(isMobile) + { + $("#mobileControllerStatusButton").show(); + $("#mobileControllerStatusAlert svg.feather.feather-alert-circle").replaceWith(feather.icons["check-circle"].toSvg()); + } + else + $("#mobileControllerStatusAlert").hide(); + $("#controllerStatusButton").show(); + $("#controllerStatusButton").html(text); + //feather.replace(); + //$("#mobileControllerStatus").removeClass('alert-success').addClass('alert-danger'); + + } + else{ + text = data.port; + $("#controllerStatusAlert").show(); + if (isMobile){ + $("#mobileControllerStatusAlert").show(); + $("#mobileControllerStatusAlert svg.feather.feather-alert-circle").replaceWith(feather.icons["check-circle"].toSvg()); + $("#mobileControllerStatusAlert").removeClass('alert-danger').addClass('alert-success'); + } + $("#controllerStatusButton").hide(); + $("#mobileControllerStatusButton").hide(); + $("#controllerStatusAlert").text(text); + $("#controllerStatusAlert").removeClass('alert-danger').addClass('alert-success'); + + //feather.replace(); + } + } +} + +function processActivateModal(data){ + var $modal, $modalTitle, $modalText + var message + //console.log(data) + if (data.modalType == "content"){ + $modal = $('#contentModal'); + $modalDialog = $('#contentDialog'); + $modalTitle = $('#contentModalTitle'); + $modalText = $('#contentModalText'); + if (data.resume=='footerSubmit'){ + $('#footerSubmit').show(); + } else { + $('#footerSubmit').hide(); + } + console.log("content modal") + //message = JSON.parse(data.message); + message = data.message; + } + else if (data.modalType == "alert") { + $modal = $('#alertModal'); + $modalDialog = $('#alertDialog'); + $modalTitle = $('#alertModalTitle'); + $modalText = $('#alertModalText'); + if (data.resume=="clear"){ + $('#clearButton').show(); + } else { + $('#clearButton').hide(); + } + //data is coming in as a jsonified string.. need to drop the extra quotes + message = JSON.parse(data.message); + } + else{ + $modal = $('#notificationModal'); + $modalDialog = $('#notificationDialog'); + $modalTitle = $('#notificationModalTitle'); + $modalText = $('#notificationModalText'); + if (data.resume=="resume"){ + $('#resumeButton').show(); + } else { + $('#resumeButton').hide(); + } + if (data.fakeServo=="fakeServo"){ + $('#fakeServoButton').show(); + } else { + $('#fakeServoButton').hide(); + } + if (data.progress=="true"){ + $('#progressBarDiv').show(); + } else { + $('#progressBarDiv').hide(); + } + if (data.progress=="spinner"){ + $('#notificationCircle').show(); + } else { + $('#notificationCircle').hide(); + } + message = data.message; + } + $modalDialog.removeClass('modal-lg'); + $modalDialog.removeClass('modal-sm'); + $modalDialog.removeClass('mw-100 w-75'); + if (data.modalSize=="large"){ + if (isMobile) + $modalDialog.addClass('modal-lg'); + else + $modalDialog.addClass('mw-100 w-75'); + } + if (data.modalSize=="medium") + $modalDialog.addClass('modal-lg'); + if (data.modalSize=="small") + $modalDialog.addClass('modal-sm'); + //$modal.data('bs.modal',null); + $modal.data('name',data.title); + + $modalTitle.html("

"+data.title+"this._items.length-1||e<0))if(this._isSliding)k(this._element).one(q.SLID,function(){return t.to(e)});else{if(n===e)return this.pause(),void this.cycle();var i=n=i.clientWidth&&n>=i.clientHeight}),u=0l[e]&&!i.escapeWithReference&&(n=Math.min(u[t],l[e]-("right"===e?u.width:u.height))),Ve({},t,n)}};return c.forEach(function(e){var t=-1!==["left","top"].indexOf(e)?"primary":"secondary";u=ze({},u,f[t](e))}),e.offsets.popper=u,e},priority:["left","right","top","bottom"],padding:5,boundariesElement:"scrollParent"},keepTogether:{order:400,enabled:!0,fn:function(e){var t=e.offsets,n=t.popper,i=t.reference,r=e.placement.split("-")[0],o=Math.floor,s=-1!==["top","bottom"].indexOf(r),a=s?"right":"bottom",l=s?"left":"top",c=s?"width":"height";return n[a]o(i[a])&&(e.offsets.popper[l]=o(i[a])),e}},arrow:{order:500,enabled:!0,fn:function(e,t){var n;if(!pt(e.instance.modifiers,"arrow","keepTogether"))return e;var i=t.element;if("string"==typeof i){if(!(i=e.instance.popper.querySelector(i)))return e}else if(!e.instance.popper.contains(i))return console.warn("WARNING: `arrow.element` must be child of its popper element!"),e;var r=e.placement.split("-")[0],o=e.offsets,s=o.popper,a=o.reference,l=-1!==["left","right"].indexOf(r),c=l?"height":"width",u=l?"Top":"Left",f=u.toLowerCase(),h=l?"left":"top",d=l?"bottom":"right",p=nt(i)[c];a[d]-ps[d]&&(e.offsets.popper[f]+=a[f]+p-s[d]),e.offsets.popper=Ge(e.offsets.popper);var m=a[f]+a[c]/2-p/2,g=Pe(e.instance.popper),_=parseFloat(g["margin"+u],10),v=parseFloat(g["border"+u+"Width"],10),y=m-e.offsets.popper[f]-_-v;return y=Math.max(Math.min(s[c]-p,y),0),e.arrowElement=i,e.offsets.arrow=(Ve(n={},f,Math.round(y)),Ve(n,h,""),n),e},element:"[x-arrow]"},flip:{order:600,enabled:!0,fn:function(p,m){if(at(p.instance.modifiers,"inner"))return p;if(p.flipped&&p.placement===p.originalPlacement)return p;var g=$e(p.instance.popper,p.instance.reference,m.padding,m.boundariesElement,p.positionFixed),_=p.placement.split("-")[0],v=it(_),y=p.placement.split("-")[1]||"",E=[];switch(m.behavior){case vt:E=[_,v];break;case yt:E=_t(_);break;case Et:E=_t(_,!0);break;default:E=m.behavior}return E.forEach(function(e,t){if(_!==e||E.length===t+1)return p;_=p.placement.split("-")[0],v=it(_);var n,i=p.offsets.popper,r=p.offsets.reference,o=Math.floor,s="left"===_&&o(i.right)>o(r.left)||"right"===_&&o(i.left)o(r.top)||"bottom"===_&&o(i.top)o(g.right),c=o(i.top)o(g.bottom),f="left"===_&&a||"right"===_&&l||"top"===_&&c||"bottom"===_&&u,h=-1!==["top","bottom"].indexOf(_),d=!!m.flipVariations&&(h&&"start"===y&&a||h&&"end"===y&&l||!h&&"start"===y&&c||!h&&"end"===y&&u);(s||f||d)&&(p.flipped=!0,(s||f)&&(_=E[t+1]),d&&(y="end"===(n=y)?"start":"start"===n?"end":n),p.placement=_+(y?"-"+y:""),p.offsets.popper=ze({},p.offsets.popper,rt(p.instance.popper,p.offsets.reference,p.placement)),p=st(p.instance.modifiers,p,"flip"))}),p},behavior:"flip",padding:5,boundariesElement:"viewport"},inner:{order:700,enabled:!1,fn:function(e){var t=e.placement,n=t.split("-")[0],i=e.offsets,r=i.popper,o=i.reference,s=-1!==["left","right"].indexOf(n),a=-1===["top","left"].indexOf(n);return r[s?"left":"top"]=o[n]-(a?r[s?"width":"height"]:0),e.placement=it(t),e.offsets.popper=Ge(r),e}},hide:{order:800,enabled:!0,fn:function(e){if(!pt(e.instance.modifiers,"hide","preventOverflow"))return e;var t=e.offsets.reference,n=ot(e.instance.modifiers,function(e){return"preventOverflow"===e.name}).boundaries;if(t.bottomn.right||t.top>n.bottom||t.rightdocument.documentElement.clientHeight;!this._isBodyOverflowing&&e&&(this._element.style.paddingLeft=this._scrollbarWidth+"px"),this._isBodyOverflowing&&!e&&(this._element.style.paddingRight=this._scrollbarWidth+"px")},e._resetAdjustments=function(){this._element.style.paddingLeft="",this._element.style.paddingRight=""},e._checkScrollbar=function(){var e=document.body.getBoundingClientRect();this._isBodyOverflowing=e.left+e.right
',trigger:"hover focus",title:"",delay:0,html:!(An={AUTO:"auto",TOP:"top",RIGHT:"right",BOTTOM:"bottom",LEFT:"left"}),selector:!(Dn={animation:"boolean",template:"string",title:"(string|element|function)",trigger:"string",delay:"(number|object)",html:"boolean",selector:"(string|boolean)",placement:"(string|function)",offset:"(number|string)",container:"(string|element|boolean)",fallbackPlacement:"(string|array)",boundary:"(string|element)"}),placement:"top",offset:0,container:!1,fallbackPlacement:"flip",boundary:"scrollParent"},Nn="out",kn={HIDE:"hide"+wn,HIDDEN:"hidden"+wn,SHOW:(On="show")+wn,SHOWN:"shown"+wn,INSERTED:"inserted"+wn,CLICK:"click"+wn,FOCUSIN:"focusin"+wn,FOCUSOUT:"focusout"+wn,MOUSEENTER:"mouseenter"+wn,MOUSELEAVE:"mouseleave"+wn},xn="fade",Pn="show",Ln=".tooltip-inner",jn=".arrow",Hn="hover",Mn="focus",Fn="click",Wn="manual",Rn=function(){function i(e,t){if("undefined"==typeof Ct)throw new TypeError("Bootstrap tooltips require Popper.js (https://popper.js.org)");this._isEnabled=!0,this._timeout=0,this._hoverState="",this._activeTrigger={},this._popper=null,this.element=e,this.config=this._getConfig(t),this.tip=null,this._setListeners()}var e=i.prototype;return e.enable=function(){this._isEnabled=!0},e.disable=function(){this._isEnabled=!1},e.toggleEnabled=function(){this._isEnabled=!this._isEnabled},e.toggle=function(e){if(this._isEnabled)if(e){var t=this.constructor.DATA_KEY,n=yn(e.currentTarget).data(t);n||(n=new this.constructor(e.currentTarget,this._getDelegateConfig()),yn(e.currentTarget).data(t,n)),n._activeTrigger.click=!n._activeTrigger.click,n._isWithActiveTrigger()?n._enter(null,n):n._leave(null,n)}else{if(yn(this.getTipElement()).hasClass(Pn))return void this._leave(null,this);this._enter(null,this)}},e.dispose=function(){clearTimeout(this._timeout),yn.removeData(this.element,this.constructor.DATA_KEY),yn(this.element).off(this.constructor.EVENT_KEY),yn(this.element).closest(".modal").off("hide.bs.modal"),this.tip&&yn(this.tip).remove(),this._isEnabled=null,this._timeout=null,this._hoverState=null,(this._activeTrigger=null)!==this._popper&&this._popper.destroy(),this._popper=null,this.element=null,this.config=null,this.tip=null},e.show=function(){var t=this;if("none"===yn(this.element).css("display"))throw new Error("Please use show on visible elements");var e=yn.Event(this.constructor.Event.SHOW);if(this.isWithContent()&&this._isEnabled){yn(this.element).trigger(e);var n=yn.contains(this.element.ownerDocument.documentElement,this.element);if(e.isDefaultPrevented()||!n)return;var i=this.getTipElement(),r=we.getUID(this.constructor.NAME);i.setAttribute("id",r),this.element.setAttribute("aria-describedby",r),this.setContent(),this.config.animation&&yn(i).addClass(xn);var o="function"==typeof this.config.placement?this.config.placement.call(this,i,this.element):this.config.placement,s=this._getAttachment(o);this.addAttachmentClass(s);var a=!1===this.config.container?document.body:yn(document).find(this.config.container);yn(i).data(this.constructor.DATA_KEY,this),yn.contains(this.element.ownerDocument.documentElement,this.tip)||yn(i).appendTo(a),yn(this.element).trigger(this.constructor.Event.INSERTED),this._popper=new Ct(this.element,i,{placement:s,modifiers:{offset:{offset:this.config.offset},flip:{behavior:this.config.fallbackPlacement},arrow:{element:jn},preventOverflow:{boundariesElement:this.config.boundary}},onCreate:function(e){e.originalPlacement!==e.placement&&t._handlePopperPlacementChange(e)},onUpdate:function(e){t._handlePopperPlacementChange(e)}}),yn(i).addClass(Pn),"ontouchstart"in document.documentElement&&yn(document.body).children().on("mouseover",null,yn.noop);var l=function(){t.config.animation&&t._fixTransition();var e=t._hoverState;t._hoverState=null,yn(t.element).trigger(t.constructor.Event.SHOWN),e===Nn&&t._leave(null,t)};if(yn(this.tip).hasClass(xn)){var c=we.getTransitionDurationFromElement(this.tip);yn(this.tip).one(we.TRANSITION_END,l).emulateTransitionEnd(c)}else l()}},e.hide=function(e){var t=this,n=this.getTipElement(),i=yn.Event(this.constructor.Event.HIDE),r=function(){t._hoverState!==On&&n.parentNode&&n.parentNode.removeChild(n),t._cleanTipClass(),t.element.removeAttribute("aria-describedby"),yn(t.element).trigger(t.constructor.Event.HIDDEN),null!==t._popper&&t._popper.destroy(),e&&e()};if(yn(this.element).trigger(i),!i.isDefaultPrevented()){if(yn(n).removeClass(Pn),"ontouchstart"in document.documentElement&&yn(document.body).children().off("mouseover",null,yn.noop),this._activeTrigger[Fn]=!1,this._activeTrigger[Mn]=!1,this._activeTrigger[Hn]=!1,yn(this.tip).hasClass(xn)){var o=we.getTransitionDurationFromElement(n);yn(n).one(we.TRANSITION_END,r).emulateTransitionEnd(o)}else r();this._hoverState=""}},e.update=function(){null!==this._popper&&this._popper.scheduleUpdate()},e.isWithContent=function(){return Boolean(this.getTitle())},e.addAttachmentClass=function(e){yn(this.getTipElement()).addClass(Tn+"-"+e)},e.getTipElement=function(){return this.tip=this.tip||yn(this.config.template)[0],this.tip},e.setContent=function(){var e=this.getTipElement();this.setElementContent(yn(e.querySelectorAll(Ln)),this.getTitle()),yn(e).removeClass(xn+" "+Pn)},e.setElementContent=function(e,t){var n=this.config.html;"object"==typeof t&&(t.nodeType||t.jquery)?n?yn(t).parent().is(e)||e.empty().append(t):e.text(yn(t).text()):e[n?"html":"text"](t)},e.getTitle=function(){var e=this.element.getAttribute("data-original-title");return e||(e="function"==typeof this.config.title?this.config.title.call(this.element):this.config.title),e},e._getAttachment=function(e){return An[e.toUpperCase()]},e._setListeners=function(){var i=this;this.config.trigger.split(" ").forEach(function(e){if("click"===e)yn(i.element).on(i.constructor.Event.CLICK,i.config.selector,function(e){return i.toggle(e)});else if(e!==Wn){var t=e===Hn?i.constructor.Event.MOUSEENTER:i.constructor.Event.FOCUSIN,n=e===Hn?i.constructor.Event.MOUSELEAVE:i.constructor.Event.FOCUSOUT;yn(i.element).on(t,i.config.selector,function(e){return i._enter(e)}).on(n,i.config.selector,function(e){return i._leave(e)})}yn(i.element).closest(".modal").on("hide.bs.modal",function(){return i.hide()})}),this.config.selector?this.config=l({},this.config,{trigger:"manual",selector:""}):this._fixTitle()},e._fixTitle=function(){var e=typeof this.element.getAttribute("data-original-title");(this.element.getAttribute("title")||"string"!==e)&&(this.element.setAttribute("data-original-title",this.element.getAttribute("title")||""),this.element.setAttribute("title",""))},e._enter=function(e,t){var n=this.constructor.DATA_KEY;(t=t||yn(e.currentTarget).data(n))||(t=new this.constructor(e.currentTarget,this._getDelegateConfig()),yn(e.currentTarget).data(n,t)),e&&(t._activeTrigger["focusin"===e.type?Mn:Hn]=!0),yn(t.getTipElement()).hasClass(Pn)||t._hoverState===On?t._hoverState=On:(clearTimeout(t._timeout),t._hoverState=On,t.config.delay&&t.config.delay.show?t._timeout=setTimeout(function(){t._hoverState===On&&t.show()},t.config.delay.show):t.show())},e._leave=function(e,t){var n=this.constructor.DATA_KEY;(t=t||yn(e.currentTarget).data(n))||(t=new this.constructor(e.currentTarget,this._getDelegateConfig()),yn(e.currentTarget).data(n,t)),e&&(t._activeTrigger["focusout"===e.type?Mn:Hn]=!1),t._isWithActiveTrigger()||(clearTimeout(t._timeout),t._hoverState=Nn,t.config.delay&&t.config.delay.hide?t._timeout=setTimeout(function(){t._hoverState===Nn&&t.hide()},t.config.delay.hide):t.hide())},e._isWithActiveTrigger=function(){for(var e in this._activeTrigger)if(this._activeTrigger[e])return!0;return!1},e._getConfig=function(e){return"number"==typeof(e=l({},this.constructor.Default,yn(this.element).data(),"object"==typeof e&&e?e:{})).delay&&(e.delay={show:e.delay,hide:e.delay}),"number"==typeof e.title&&(e.title=e.title.toString()),"number"==typeof e.content&&(e.content=e.content.toString()),we.typeCheckConfig(En,e,this.constructor.DefaultType),e},e._getDelegateConfig=function(){var e={};if(this.config)for(var t in this.config)this.constructor.Default[t]!==this.config[t]&&(e[t]=this.config[t]);return e},e._cleanTipClass=function(){var e=yn(this.getTipElement()),t=e.attr("class").match(Sn);null!==t&&t.length&&e.removeClass(t.join(""))},e._handlePopperPlacementChange=function(e){var t=e.instance;this.tip=t.popper,this._cleanTipClass(),this.addAttachmentClass(this._getAttachment(e.placement))},e._fixTransition=function(){var e=this.getTipElement(),t=this.config.animation;null===e.getAttribute("x-placement")&&(yn(e).removeClass(xn),this.config.animation=!1,this.hide(),this.show(),this.config.animation=t)},i._jQueryInterface=function(n){return this.each(function(){var e=yn(this).data(bn),t="object"==typeof n&&n;if((e||!/dispose|hide/.test(n))&&(e||(e=new i(this,t),yn(this).data(bn,e)),"string"==typeof n)){if("undefined"==typeof e[n])throw new TypeError('No method named "'+n+'"');e[n]()}})},s(i,null,[{key:"VERSION",get:function(){return"4.1.3"}},{key:"Default",get:function(){return In}},{key:"NAME",get:function(){return En}},{key:"DATA_KEY",get:function(){return bn}},{key:"Event",get:function(){return kn}},{key:"EVENT_KEY",get:function(){return wn}},{key:"DefaultType",get:function(){return Dn}}]),i}(),yn.fn[En]=Rn._jQueryInterface,yn.fn[En].Constructor=Rn,yn.fn[En].noConflict=function(){return yn.fn[En]=Cn,Rn._jQueryInterface},Rn),Qi=(Bn="popover",Kn="."+(qn="bs.popover"),Qn=(Un=t).fn[Bn],Yn="bs-popover",Vn=new RegExp("(^|\\s)"+Yn+"\\S+","g"),zn=l({},Ki.Default,{placement:"right",trigger:"click",content:"",template:''}),Gn=l({},Ki.DefaultType,{content:"(string|element|function)"}),Jn="fade",Xn=".popover-header",$n=".popover-body",ei={HIDE:"hide"+Kn,HIDDEN:"hidden"+Kn,SHOW:(Zn="show")+Kn,SHOWN:"shown"+Kn,INSERTED:"inserted"+Kn,CLICK:"click"+Kn,FOCUSIN:"focusin"+Kn,FOCUSOUT:"focusout"+Kn,MOUSEENTER:"mouseenter"+Kn,MOUSELEAVE:"mouseleave"+Kn},ti=function(e){var t,n;function i(){return e.apply(this,arguments)||this}n=e,(t=i).prototype=Object.create(n.prototype),(t.prototype.constructor=t).__proto__=n;var r=i.prototype;return r.isWithContent=function(){return this.getTitle()||this._getContent()},r.addAttachmentClass=function(e){Un(this.getTipElement()).addClass(Yn+"-"+e)},r.getTipElement=function(){return this.tip=this.tip||Un(this.config.template)[0],this.tip},r.setContent=function(){var e=Un(this.getTipElement());this.setElementContent(e.find(Xn),this.getTitle());var t=this._getContent();"function"==typeof t&&(t=t.call(this.element)),this.setElementContent(e.find($n),t),e.removeClass(Jn+" "+Zn)},r._getContent=function(){return this.element.getAttribute("data-content")||this.config.content},r._cleanTipClass=function(){var e=Un(this.getTipElement()),t=e.attr("class").match(Vn);null!==t&&0=this._offsets[r]&&("undefined"==typeof this._offsets[r+1]||e/g,">")},graphemeSplit:function(t){var e,i=0,r=[];for(i=0;i/i,"")));if(!e||!e.documentElement)return n&&n(null),!1;C.parseSVGDocument(e.documentElement,function(t,e,i,r){n&&n(t,e,i,r)},i,r)}})},loadSVGFromString:function(t,n,e,i){var r;if(t=t.trim(),"undefined"!=typeof DOMParser){var s=new DOMParser;s&&s.parseFromString&&(r=s.parseFromString(t,"text/xml"))}else C.window.ActiveXObject&&((r=new ActiveXObject("Microsoft.XMLDOM")).async="false",r.loadXML(t.replace(//i,"")));C.parseSVGDocument(r.documentElement,function(t,e,i,r){n(t,e,i,r)},e,i)}})}("undefined"!=typeof exports?exports:this),fabric.ElementsParser=function(t,e,i,r,n){this.elements=t,this.callback=e,this.options=i,this.reviver=r,this.svgUid=i&&i.svgUid||0,this.parsingOptions=n,this.regexUrl=/^url\(['"]?#([^'"]+)['"]?\)/g},function(t){t.parse=function(){this.instances=new Array(this.elements.length),this.numElements=this.elements.length,this.createObjects()},t.createObjects=function(){var i=this;this.elements.forEach(function(t,e){t.setAttribute("svgUid",i.svgUid),i.createObject(t,e)})},t.findTag=function(t){return fabric[fabric.util.string.capitalize(t.tagName.replace("svg:",""))]},t.createObject=function(t,e){var i=this.findTag(t);if(i&&i.fromElement)try{i.fromElement(t,this.createCallback(e,t),this.options)}catch(t){fabric.log(t)}else this.checkIfDone()},t.createCallback=function(i,r){var n=this;return function(t){var e;n.resolveGradient(t,"fill"),n.resolveGradient(t,"stroke"),t instanceof fabric.Image&&(e=t.parsePreserveAspectRatioAttribute(r)),t._removeTransformMatrix(e),n.resolveClipPath(t),n.reviver&&n.reviver(r,t),n.instances[i]=t,n.checkIfDone()}},t.extractPropertyDefinition=function(t,e,i){var r=t[e];if(/^url\(/.test(r)){var n=this.regexUrl.exec(r)[1];return this.regexUrl.lastIndex=0,fabric[i][this.svgUid][n]}},t.resolveGradient=function(t,e){var i=this.extractPropertyDefinition(t,e,"gradientDefs");i&&t.set(e,fabric.Gradient.fromElement(i,t))},t.createClipPathCallback=function(t,e){return function(t){t._removeTransformMatrix(),t.fillRule=t.clipRule,e.push(t)}},t.resolveClipPath=function(t){var e,i,r,n,s=this.extractPropertyDefinition(t,"clipPath","clipPaths");if(s){r=[],i=fabric.util.invertTransform(t.calcTransformMatrix());for(var o=0;ot.x&&this.y>t.y},gte:function(t){return this.x>=t.x&&this.y>=t.y},lerp:function(t,e){return void 0===e&&(e=.5),e=Math.max(Math.min(1,e),0),new i(this.x+(t.x-this.x)*e,this.y+(t.y-this.y)*e)},distanceFrom:function(t){var e=this.x-t.x,i=this.y-t.y;return Math.sqrt(e*e+i*i)},midPointFrom:function(t){return this.lerp(t)},min:function(t){return new i(Math.min(this.x,t.x),Math.min(this.y,t.y))},max:function(t){return new i(Math.max(this.x,t.x),Math.max(this.y,t.y))},toString:function(){return this.x+","+this.y},setXY:function(t,e){return this.x=t,this.y=e,this},setX:function(t){return this.x=t,this},setY:function(t){return this.y=t,this},setFromPoint:function(t){return this.x=t.x,this.y=t.y,this},swap:function(t){var e=this.x,i=this.y;this.x=t.x,this.y=t.y,t.x=e,t.y=i},clone:function(){return new i(this.x,this.y)}}}("undefined"!=typeof exports?exports:this),function(t){"use strict";var f=t.fabric||(t.fabric={});function d(t){this.status=t,this.points=[]}f.Intersection?f.warn("fabric.Intersection is already defined"):(f.Intersection=d,f.Intersection.prototype={constructor:d,appendPoint:function(t){return this.points.push(t),this},appendPoints:function(t){return this.points=this.points.concat(t),this}},f.Intersection.intersectLineLine=function(t,e,i,r){var n,s=(r.x-i.x)*(t.y-i.y)-(r.y-i.y)*(t.x-i.x),o=(e.x-t.x)*(t.y-i.y)-(e.y-t.y)*(t.x-i.x),a=(r.y-i.y)*(e.x-t.x)-(r.x-i.x)*(e.y-t.y);if(0!==a){var h=s/a,c=o/a;0<=h&&h<=1&&0<=c&&c<=1?(n=new d("Intersection")).appendPoint(new f.Point(t.x+h*(e.x-t.x),t.y+h*(e.y-t.y))):n=new d}else n=new d(0===s||0===o?"Coincident":"Parallel");return n},f.Intersection.intersectLinePolygon=function(t,e,i){var r,n,s,o,a=new d,h=i.length;for(o=0;os.r2,h=t.width/2,c=t.height/2;for(var l in o.sort(function(t,e){return t.offset-e.offset}),"path"===t.type&&(h-=t.pathOffset.x,c-=t.pathOffset.y),s)"x1"===l||"x2"===l?s[l]+=this.offsetX-h:"y1"!==l&&"y2"!==l||(s[l]+=this.offsetY-c);if(n='id="SVGID_'+this.id+'" gradientUnits="userSpaceOnUse"',this.gradientTransform&&(n+=' gradientTransform="matrix('+this.gradientTransform.join(" ")+')" '),"linear"===this.type?r=["\n']:"radial"===this.type&&(r=["\n']),"radial"===this.type){if(a)for((o=o.concat()).reverse(),e=0,i=o.length;e\n')}return r.push("linear"===this.type?"\n":"\n"),r.join("")},toLive:function(t){var e,i,r,n=fabric.util.object.clone(this.coords);if(this.type){for("linear"===this.type?e=t.createLinearGradient(n.x1,n.y1,n.x2,n.y2):"radial"===this.type&&(e=t.createRadialGradient(n.x1,n.y1,n.r1,n.x2,n.y2,n.r2)),i=0,r=this.colorStops.length;i\n\n\n'},setOptions:function(t){for(var e in t)this[e]=t[e]},toLive:function(t){var e="function"==typeof this.source?this.source():this.source;if(!e)return"";if(void 0!==e.src){if(!e.complete)return"";if(0===e.naturalWidth||0===e.naturalHeight)return""}return t.createPattern(e,this.repeat)}})}(),function(t){"use strict";var o=t.fabric||(t.fabric={}),a=o.util.toFixed;o.Shadow?o.warn("fabric.Shadow is already defined."):(o.Shadow=o.util.createClass({color:"rgb(0,0,0)",blur:0,offsetX:0,offsetY:0,affectStroke:!1,includeDefaultValues:!0,initialize:function(t){for(var e in"string"==typeof t&&(t=this._parseShadow(t)),t)this[e]=t[e];this.id=o.Object.__uid++},_parseShadow:function(t){var e=t.trim(),i=o.Shadow.reOffsetsAndBlur.exec(e)||[];return{color:(e.replace(o.Shadow.reOffsetsAndBlur,"")||"rgb(0,0,0)").trim(),offsetX:parseInt(i[1],10)||0,offsetY:parseInt(i[2],10)||0,blur:parseInt(i[3],10)||0}},toString:function(){return[this.offsetX,this.offsetY,this.blur,this.color].join("px ")},toSVG:function(t){var e=40,i=40,r=o.Object.NUM_FRACTION_DIGITS,n=o.util.rotateVector({x:this.offsetX,y:this.offsetY},o.util.degreesToRadians(-t.angle)),s=new o.Color(this.color);return t.width&&t.height&&(e=100*a((Math.abs(n.x)+this.blur)/t.width,r)+20,i=100*a((Math.abs(n.y)+this.blur)/t.height,r)+20),t.flipX&&(n.x*=-1),t.flipY&&(n.y*=-1),'\n\t\n\t\n\t\n\t\n\t\n\t\t\n\t\t\n\t\n\n'},toObject:function(){if(this.includeDefaultValues)return{color:this.color,blur:this.blur,offsetX:this.offsetX,offsetY:this.offsetY,affectStroke:this.affectStroke};var e={},i=o.Shadow.prototype;return["color","blur","offsetX","offsetY","affectStroke"].forEach(function(t){this[t]!==i[t]&&(e[t]=this[t])},this),e}}),o.Shadow.reOffsetsAndBlur=/(?:\s|^)(-?\d+(?:px)?(?:\s?|$))?(-?\d+(?:px)?(?:\s?|$))?(\d+(?:px)?)?(?:\s?|$)(?:$|\s)/)}("undefined"!=typeof exports?exports:this),function(){"use strict";if(fabric.StaticCanvas)fabric.warn("fabric.StaticCanvas is already defined.");else{var n=fabric.util.object.extend,t=fabric.util.getElementOffset,c=fabric.util.removeFromArray,a=fabric.util.toFixed,s=fabric.util.transformPoint,o=fabric.util.invertTransform,e=new Error("Could not initialize `canvas` element");fabric.StaticCanvas=fabric.util.createClass(fabric.CommonMethods,{initialize:function(t,e){e||(e={}),this.renderAndResetBound=this.renderAndReset.bind(this),this.requestRenderAllBound=this.requestRenderAll.bind(this),this._initStatic(t,e)},backgroundColor:"",backgroundImage:null,overlayColor:"",overlayImage:null,includeDefaultValues:!0,stateful:!1,renderOnAddRemove:!0,clipTo:null,controlsAboveOverlay:!1,allowTouchScrolling:!1,imageSmoothingEnabled:!0,viewportTransform:fabric.iMatrix.concat(),backgroundVpt:!0,overlayVpt:!0,onBeforeScaleRotate:function(){},enableRetinaScaling:!0,vptCoords:{},skipOffscreen:!0,clipPath:void 0,_initStatic:function(t,e){var i=this.requestRenderAllBound;this._objects=[],this._createLowerCanvas(t),this._initOptions(e),this._setImageSmoothing(),this.interactive||this._initRetinaScaling(),e.overlayImage&&this.setOverlayImage(e.overlayImage,i),e.backgroundImage&&this.setBackgroundImage(e.backgroundImage,i),e.backgroundColor&&this.setBackgroundColor(e.backgroundColor,i),e.overlayColor&&this.setOverlayColor(e.overlayColor,i),this.calcOffset()},_isRetinaScaling:function(){return 1!==fabric.devicePixelRatio&&this.enableRetinaScaling},getRetinaScaling:function(){return this._isRetinaScaling()?fabric.devicePixelRatio:1},_initRetinaScaling:function(){this._isRetinaScaling()&&(this.lowerCanvasEl.setAttribute("width",this.width*fabric.devicePixelRatio),this.lowerCanvasEl.setAttribute("height",this.height*fabric.devicePixelRatio),this.contextContainer.scale(fabric.devicePixelRatio,fabric.devicePixelRatio))},calcOffset:function(){return this._offset=t(this.lowerCanvasEl),this},setOverlayImage:function(t,e,i){return this.__setBgOverlayImage("overlayImage",t,e,i)},setBackgroundImage:function(t,e,i){return this.__setBgOverlayImage("backgroundImage",t,e,i)},setOverlayColor:function(t,e){return this.__setBgOverlayColor("overlayColor",t,e)},setBackgroundColor:function(t,e){return this.__setBgOverlayColor("backgroundColor",t,e)},_setImageSmoothing:function(){var t=this.getContext();t.imageSmoothingEnabled=t.imageSmoothingEnabled||t.webkitImageSmoothingEnabled||t.mozImageSmoothingEnabled||t.msImageSmoothingEnabled||t.oImageSmoothingEnabled,t.imageSmoothingEnabled=this.imageSmoothingEnabled},__setBgOverlayImage:function(e,t,i,r){return"string"==typeof t?fabric.util.loadImage(t,function(t){t&&(this[e]=new fabric.Image(t,r)),i&&i(t)},this,r&&r.crossOrigin):(r&&t.setOptions(r),this[e]=t,i&&i(t)),this},__setBgOverlayColor:function(t,e,i){return this[t]=e,this._initGradient(e,t),this._initPattern(e,t,i),this},_createCanvasElement:function(){var t=fabric.util.createCanvasElement();if(!t)throw e;if(t.style||(t.style={}),void 0===t.getContext)throw e;return t},_initOptions:function(t){this._setOptions(t),this.width=this.width||parseInt(this.lowerCanvasEl.width,10)||0,this.height=this.height||parseInt(this.lowerCanvasEl.height,10)||0,this.lowerCanvasEl.style&&(this.lowerCanvasEl.width=this.width,this.lowerCanvasEl.height=this.height,this.lowerCanvasEl.style.width=this.width+"px",this.lowerCanvasEl.style.height=this.height+"px",this.viewportTransform=this.viewportTransform.slice())},_createLowerCanvas:function(t){t&&t.getContext?this.lowerCanvasEl=t:this.lowerCanvasEl=fabric.util.getById(t)||this._createCanvasElement(),fabric.util.addClass(this.lowerCanvasEl,"lower-canvas"),this.interactive&&this._applyCanvasStyle(this.lowerCanvasEl),this.contextContainer=this.lowerCanvasEl.getContext("2d")},getWidth:function(){return this.width},getHeight:function(){return this.height},setWidth:function(t,e){return this.setDimensions({width:t},e)},setHeight:function(t,e){return this.setDimensions({height:t},e)},setDimensions:function(t,e){var i;for(var r in e=e||{},t)i=t[r],e.cssOnly||(this._setBackstoreDimension(r,t[r]),i+="px",this.hasLostContext=!0),e.backstoreOnly||this._setCssDimension(r,i);return this._isCurrentlyDrawing&&this.freeDrawingBrush&&this.freeDrawingBrush._setBrushStyles(),this._initRetinaScaling(),this._setImageSmoothing(),this.calcOffset(),e.cssOnly||this.requestRenderAll(),this},_setBackstoreDimension:function(t,e){return this.lowerCanvasEl[t]=e,this.upperCanvasEl&&(this.upperCanvasEl[t]=e),this.cacheCanvasEl&&(this.cacheCanvasEl[t]=e),this[t]=e,this},_setCssDimension:function(t,e){return this.lowerCanvasEl.style[t]=e,this.upperCanvasEl&&(this.upperCanvasEl.style[t]=e),this.wrapperEl&&(this.wrapperEl.style[t]=e),this},getZoom:function(){return this.viewportTransform[0]},setViewportTransform:function(t){var e,i,r,n=this._activeObject;for(this.viewportTransform=t,i=0,r=this._objects.length;i"),i.join("")},_setSVGPreamble:function(t,e){e.suppressPreamble||t.push('\n','\n')},_setSVGHeader:function(t,e){var i,r=e.width||this.width,n=e.height||this.height,s='viewBox="0 0 '+this.width+" "+this.height+'" ',o=fabric.Object.NUM_FRACTION_DIGITS;e.viewBox?s='viewBox="'+e.viewBox.x+" "+e.viewBox.y+" "+e.viewBox.width+" "+e.viewBox.height+'" ':this.svgViewportTransformation&&(i=this.viewportTransform,s='viewBox="'+a(-i[4]/i[0],o)+" "+a(-i[5]/i[3],o)+" "+a(this.width/i[0],o)+" "+a(this.height/i[3],o)+'" '),t.push("\n',"Created with Fabric.js ",fabric.version,"\n","\n",this.createSVGFontFacesMarkup(),this.createSVGRefElementsMarkup(),"\n")},createSVGRefElementsMarkup:function(){var i=this;return["backgroundColor","overlayColor"].map(function(t){var e=i[t];if(e&&e.toLive)return e.toSVG(i,!1)}).join("")},createSVGFontFacesMarkup:function(){var t,e,i,r,n,s,o,a,h="",c={},l=fabric.fontPaths,u=this._objects;for(o=0,a=u.length;o',"\n",h,"","\n"].join("")),h},_setSVGObjects:function(t,e){var i,r,n,s=this._objects;for(r=0,n=s.length;r\n")}else t.push('\n")},sendToBack:function(t){if(!t)return this;var e,i,r,n=this._activeObject;if(t===n&&"activeSelection"===t.type)for(e=(r=n._objects).length;e--;)i=r[e],c(this._objects,i),this._objects.unshift(i);else c(this._objects,t),this._objects.unshift(t);return this.renderOnAddRemove&&this.requestRenderAll(),this},bringToFront:function(t){if(!t)return this;var e,i,r,n=this._activeObject;if(t===n&&"activeSelection"===t.type)for(r=n._objects,e=0;e"}}),n(fabric.StaticCanvas.prototype,fabric.Observable),n(fabric.StaticCanvas.prototype,fabric.Collection),n(fabric.StaticCanvas.prototype,fabric.DataURLExporter),n(fabric.StaticCanvas,{EMPTY_JSON:'{"objects": [], "background": "white"}',supports:function(t){var e=fabric.util.createCanvasElement();if(!e||!e.getContext)return null;var i=e.getContext("2d");if(!i)return null;switch(t){case"getImageData":return void 0!==i.getImageData;case"setLineDash":return void 0!==i.setLineDash;case"toDataURL":return void 0!==e.toDataURL;case"toDataURLWithQuality":try{return e.toDataURL("image/jpeg",0),!0}catch(t){}return!1;default:return null}}}),fabric.StaticCanvas.prototype.toJSON=fabric.StaticCanvas.prototype.toObject,fabric.isLikelyNode&&(fabric.StaticCanvas.prototype.createPNGStream=function(){var t=fabric.util.getNodeCanvas(this.lowerCanvasEl);return t&&t.createPNGStream()},fabric.StaticCanvas.prototype.createJPEGStream=function(t){var e=fabric.util.getNodeCanvas(this.lowerCanvasEl);return e&&e.createJPEGStream(t)})}}(),fabric.BaseBrush=fabric.util.createClass({color:"rgb(0, 0, 0)",width:1,shadow:null,strokeLineCap:"round",strokeLineJoin:"round",strokeMiterLimit:10,strokeDashArray:null,setShadow:function(t){return this.shadow=new fabric.Shadow(t),this},_setBrushStyles:function(){var t=this.canvas.contextTop;t.strokeStyle=this.color,t.lineWidth=this.width,t.lineCap=this.strokeLineCap,t.miterLimit=this.strokeMiterLimit,t.lineJoin=this.strokeLineJoin,fabric.StaticCanvas.supports("setLineDash")&&t.setLineDash(this.strokeDashArray||[])},_saveAndTransform:function(t){var e=this.canvas.viewportTransform;t.save(),t.transform(e[0],e[1],e[2],e[3],e[4],e[5])},_setShadow:function(){if(this.shadow){var t=this.canvas.contextTop,e=this.canvas.getZoom();t.shadowColor=this.shadow.color,t.shadowBlur=this.shadow.blur*e,t.shadowOffsetX=this.shadow.offsetX*e,t.shadowOffsetY=this.shadow.offsetY*e}},_resetShadow:function(){var t=this.canvas.contextTop;t.shadowColor="",t.shadowBlur=t.shadowOffsetX=t.shadowOffsetY=0}}),fabric.PencilBrush=fabric.util.createClass(fabric.BaseBrush,{initialize:function(t){this.canvas=t,this._points=[]},_drawSegment:function(t,e,i){var r=e.midPointFrom(i);return t.quadraticCurveTo(e.x,e.y,r.x,r.y),r},onMouseDown:function(t){this._prepareForDrawing(t),this._captureDrawingPath(t),this._render()},onMouseMove:function(t){if(this._captureDrawingPath(t)&&1t[e-2].x?1:n.x===t[e-2].x?0:-1,h=n.y>t[e-2].y?1:n.y===t[e-2].y?0:-1),i.push("L ",n.x+a*r," ",n.y+h*r),i},createPath:function(t){var e=new fabric.Path(t,{fill:null,stroke:this.color,strokeWidth:this.width,strokeLineCap:this.strokeLineCap,strokeMiterLimit:this.strokeMiterLimit,strokeLineJoin:this.strokeLineJoin,strokeDashArray:this.strokeDashArray}),i=new fabric.Point(e.left+e.width/2,e.top+e.height/2);return i=e.translateToGivenOrigin(i,"center","center",e.originX,e.originY),e.top=i.y,e.left=i.x,this.shadow&&(this.shadow.affectStroke=!0,e.setShadow(this.shadow)),e},_finalizeAndAddPath:function(){this.canvas.contextTop.closePath();var t=this.convertPointsToSVGPath(this._points).join("");if("M 0 0 Q 0 0 0 0 L 0 0"!==t){var e=this.createPath(t);this.canvas.clearContext(this.canvas.contextTop),this.canvas.add(e),this.canvas.renderAll(),e.setCoords(),this._resetShadow(),this.canvas.fire("path:created",{path:e})}else this.canvas.requestRenderAll()}}),fabric.CircleBrush=fabric.util.createClass(fabric.BaseBrush,{width:10,initialize:function(t){this.canvas=t,this.points=[]},drawDot:function(t){var e=this.addPoint(t),i=this.canvas.contextTop;this._saveAndTransform(i),i.fillStyle=e.fill,i.beginPath(),i.arc(e.x,e.y,e.radius,0,2*Math.PI,!1),i.closePath(),i.fill(),i.restore()},onMouseDown:function(t){this.points.length=0,this.canvas.clearContext(this.canvas.contextTop),this._setShadow(),this.drawDot(t)},_render:function(){var t,e,i,r=this.canvas.contextTop,n=this.points;for(this._saveAndTransform(r),t=0,e=n.length;tn?t.x<0?t.x+=n:t.x-=n:t.x=0,c(t.y)>n?t.y<0?t.y+=n:t.y-=n:t.y=0},_rotateObject:function(t,e){var i=this._currentTransform,r=i.target,n=r.translateToOriginPoint(r.getCenterPoint(),i.originX,i.originY);if(r.lockRotation)return!1;var s=g(i.ey-n.y,i.ex-n.x),o=g(e-n.y,t-n.x),a=d(o-s+i.theta),h=!0;if(0"},getObjectScaling:function(){var t=this.scaleX,e=this.scaleY;if(this.group){var i=this.group.getObjectScaling();t*=i.scaleX,e*=i.scaleY}return{scaleX:t,scaleY:e}},getTotalObjectScaling:function(){var t=this.getObjectScaling(),e=t.scaleX,i=t.scaleY;if(this.canvas){var r=this.canvas.getZoom(),n=this.canvas.getRetinaScaling();e*=r*n,i*=r*n}return{scaleX:e,scaleY:i}},getObjectOpacity:function(){var t=this.opacity;return this.group&&(t*=this.group.getObjectOpacity()),t},_set:function(t,e){var i="scaleX"===t||"scaleY"===t,r=this[t]!==e,n=!1;return i&&(e=this._constrainScale(e)),"scaleX"===t&&e<0?(this.flipX=!this.flipX,e*=-1):"scaleY"===t&&e<0?(this.flipY=!this.flipY,e*=-1):"shadow"!==t||!e||e instanceof x.Shadow?"dirty"===t&&this.group&&this.group.set("dirty",e):e=new x.Shadow(e),this[t]=e,r&&(n=this.group&&this.group.isOnACache(),-1=t.x&&n.left+n.width<=e.x&&n.top>=t.y&&n.top+n.height<=e.y},containsPoint:function(t,e,i,r){e=e||this._getImageLines(r?this.calcCoords(i):i?this.aCoords:this.oCoords);var n=this._findCrossPoints(t,e);return 0!==n&&n%2==1},isOnScreen:function(t){if(!this.canvas)return!1;for(var e,i=this.canvas.vptCoords.tl,r=this.canvas.vptCoords.br,n=this.getCoords(!0,t),s=0;s<4;s++)if((e=n[s]).x<=r.x&&e.x>=i.x&&e.y<=r.y&&e.y>=i.y)return!0;return!!this.intersectsWithRect(i,r,!0,t)||this._containsCenterOfCanvas(i,r,t)},_containsCenterOfCanvas:function(t,e,i){var r={x:(t.x+e.x)/2,y:(t.y+e.y)/2};return!!this.containsPoint(r,null,!0,i)},isPartiallyOnScreen:function(t){if(!this.canvas)return!1;var e=this.canvas.vptCoords.tl,i=this.canvas.vptCoords.br;return!!this.intersectsWithRect(e,i,!0,t)||this._containsCenterOfCanvas(e,i,t)},_getImageLines:function(t){return{topline:{o:t.tl,d:t.tr},rightline:{o:t.tr,d:t.br},bottomline:{o:t.br,d:t.bl},leftline:{o:t.bl,d:t.tl}}},_findCrossPoints:function(t,e){var i,r,n,s=0;for(var o in e)if(!((n=e[o]).o.y=t.y&&n.d.y>=t.y||(n.o.x===n.d.x&&n.o.x>=t.x?r=n.o.x:(0,i=(n.d.y-n.o.y)/(n.d.x-n.o.x),r=-(t.y-0*t.x-(n.o.y-i*n.o.x))/(0-i)),r>=t.x&&(s+=1),2!==s)))break;return s},getBoundingRect:function(t,e){var i=this.getCoords(t,e);return fabric.util.makeBoundingBoxFromPoints(i)},getScaledWidth:function(){return this._getTransformedDimensions().x},getScaledHeight:function(){return this._getTransformedDimensions().y},_constrainScale:function(t){return Math.abs(t)\n')}},_createBaseSVGMarkup:function(){var t=[],e=this.clipPath;return this.fill&&this.fill.toLive&&t.push(this.fill.toSVG(this,!1)),this.stroke&&this.stroke.toLive&&t.push(this.stroke.toSVG(this,!1)),this.shadow&&t.push(this.shadow.toSVG(this)),e&&(e.clipPathId="CLIPPATH_"+fabric.Object.__uid++,t.push('\n\t',this.clipPath.toSVG(),"\n")),t},addPaintOrder:function(){return"fill"!==this.paintFirst?' paint-order="'+this.paintFirst+'" ':""}})}(),function(){var n=fabric.util.object.extend,r="stateProperties";function s(e,t,i){var r={};i.forEach(function(t){r[t]=e[t]}),n(e[t],r,!0)}fabric.util.object.extend(fabric.Object.prototype,{hasStateChanged:function(t){var e="_"+(t=t||r);return Object.keys(this[e]).length\n'),t?t(e.join("")):e.join("")}}),s.Line.ATTRIBUTE_NAMES=s.SHARED_ATTRIBUTES.concat("x1 y1 x2 y2".split(" ")),s.Line.fromElement=function(t,e,i){i=i||{};var r=s.parseAttributes(t,s.Line.ATTRIBUTE_NAMES),n=[r.x1||0,r.y1||0,r.x2||0,r.y2||0];e(new s.Line(n,o(r,i)))},s.Line.fromObject=function(t,e){var i=r(t,!0);i.points=[t.x1,t.y1,t.x2,t.y2],s.Object._fromObject("Line",i,function(t){delete t.points,e&&e(t)},"points")})}("undefined"!=typeof exports?exports:this),function(t){"use strict";var h=t.fabric||(t.fabric={}),c=Math.PI;h.Circle?h.warn("fabric.Circle is already defined."):(h.Circle=h.util.createClass(h.Object,{type:"circle",radius:0,startAngle:0,endAngle:2*c,cacheProperties:h.Object.prototype.cacheProperties.concat("radius","startAngle","endAngle"),_set:function(t,e){return this.callSuper("_set",t,e),"radius"===t&&this.setRadius(e),this},toObject:function(t){return this.callSuper("toObject",["radius","startAngle","endAngle"].concat(t))},toSVG:function(t){var e=this._createBaseSVGMarkup(),i=(this.endAngle-this.startAngle)%(2*c);if(0===i)e.push("\n");else{var r=h.util.cos(this.startAngle)*this.radius,n=h.util.sin(this.startAngle)*this.radius,s=h.util.cos(this.endAngle)*this.radius,o=h.util.sin(this.endAngle)*this.radius,a=c\n")}return t?t(e.join("")):e.join("")},_render:function(t){t.beginPath(),t.arc(0,0,this.radius,this.startAngle,this.endAngle,!1),this._renderPaintInOrder(t)},getRadiusX:function(){return this.get("radius")*this.get("scaleX")},getRadiusY:function(){return this.get("radius")*this.get("scaleY")},setRadius:function(t){return this.radius=t,this.set("width",2*t).set("height",2*t)}}),h.Circle.ATTRIBUTE_NAMES=h.SHARED_ATTRIBUTES.concat("cx cy r".split(" ")),h.Circle.fromElement=function(t,e){var i,r=h.parseAttributes(t,h.Circle.ATTRIBUTE_NAMES);if(!("radius"in(i=r)&&0<=i.radius))throw new Error("value of `r` attribute is required and can not be negative");r.left=(r.left||0)-r.radius,r.top=(r.top||0)-r.radius,e(new h.Circle(r))},h.Circle.fromObject=function(t,e){return h.Object._fromObject("Circle",t,e)})}("undefined"!=typeof exports?exports:this),function(t){"use strict";var r=t.fabric||(t.fabric={});r.Triangle?r.warn("fabric.Triangle is already defined"):(r.Triangle=r.util.createClass(r.Object,{type:"triangle",width:100,height:100,_render:function(t){var e=this.width/2,i=this.height/2;t.beginPath(),t.moveTo(-e,i),t.lineTo(0,-i),t.lineTo(e,i),t.closePath(),this._renderPaintInOrder(t)},_renderDashedStroke:function(t){var e=this.width/2,i=this.height/2;t.beginPath(),r.util.drawDashedLine(t,-e,i,0,-i,this.strokeDashArray),r.util.drawDashedLine(t,0,-i,e,i,this.strokeDashArray),r.util.drawDashedLine(t,e,i,-e,i,this.strokeDashArray),t.closePath()},toSVG:function(t){var e=this._createBaseSVGMarkup(),i=this.width/2,r=this.height/2,n=[-i+" "+r,"0 "+-r,i+" "+r].join(",");return e.push(""),t?t(e.join("")):e.join("")}}),r.Triangle.fromObject=function(t,e){return r.Object._fromObject("Triangle",t,e)})}("undefined"!=typeof exports?exports:this),function(t){"use strict";var r=t.fabric||(t.fabric={}),e=2*Math.PI;r.Ellipse?r.warn("fabric.Ellipse is already defined."):(r.Ellipse=r.util.createClass(r.Object,{type:"ellipse",rx:0,ry:0,cacheProperties:r.Object.prototype.cacheProperties.concat("rx","ry"),initialize:function(t){this.callSuper("initialize",t),this.set("rx",t&&t.rx||0),this.set("ry",t&&t.ry||0)},_set:function(t,e){switch(this.callSuper("_set",t,e),t){case"rx":this.rx=e,this.set("width",2*e);break;case"ry":this.ry=e,this.set("height",2*e)}return this},getRx:function(){return this.get("rx")*this.get("scaleX")},getRy:function(){return this.get("ry")*this.get("scaleY")},toObject:function(t){return this.callSuper("toObject",["rx","ry"].concat(t))},toSVG:function(t){var e=this._createBaseSVGMarkup();return e.push("\n"),t?t(e.join("")):e.join("")},_render:function(t){t.beginPath(),t.save(),t.transform(1,0,0,this.ry/this.rx,0,0),t.arc(0,0,this.rx,0,e,!1),t.restore(),this._renderPaintInOrder(t)}}),r.Ellipse.ATTRIBUTE_NAMES=r.SHARED_ATTRIBUTES.concat("cx cy rx ry".split(" ")),r.Ellipse.fromElement=function(t,e){var i=r.parseAttributes(t,r.Ellipse.ATTRIBUTE_NAMES);i.left=(i.left||0)-i.rx,i.top=(i.top||0)-i.ry,e(new r.Ellipse(i))},r.Ellipse.fromObject=function(t,e){return r.Object._fromObject("Ellipse",t,e)})}("undefined"!=typeof exports?exports:this),function(t){"use strict";var s=t.fabric||(t.fabric={}),o=s.util.object.extend;s.Rect?s.warn("fabric.Rect is already defined"):(s.Rect=s.util.createClass(s.Object,{stateProperties:s.Object.prototype.stateProperties.concat("rx","ry"),type:"rect",rx:0,ry:0,cacheProperties:s.Object.prototype.cacheProperties.concat("rx","ry"),initialize:function(t){this.callSuper("initialize",t),this._initRxRy()},_initRxRy:function(){this.rx&&!this.ry?this.ry=this.rx:this.ry&&!this.rx&&(this.rx=this.ry)},_render:function(t){if(1!==this.width||1!==this.height){var e=this.rx?Math.min(this.rx,this.width/2):0,i=this.ry?Math.min(this.ry,this.height/2):0,r=this.width,n=this.height,s=-this.width/2,o=-this.height/2,a=0!==e||0!==i,h=.4477152502;t.beginPath(),t.moveTo(s+e,o),t.lineTo(s+r-e,o),a&&t.bezierCurveTo(s+r-h*e,o,s+r,o+h*i,s+r,o+i),t.lineTo(s+r,o+n-i),a&&t.bezierCurveTo(s+r,o+n-h*i,s+r-h*e,o+n,s+r-e,o+n),t.lineTo(s+e,o+n),a&&t.bezierCurveTo(s+h*e,o+n,s,o+n-h*i,s,o+n-i),t.lineTo(s,o+i),a&&t.bezierCurveTo(s,o+h*i,s+h*e,o,s+e,o),t.closePath(),this._renderPaintInOrder(t)}else t.fillRect(-.5,-.5,1,1)},_renderDashedStroke:function(t){var e=-this.width/2,i=-this.height/2,r=this.width,n=this.height;t.beginPath(),s.util.drawDashedLine(t,e,i,e+r,i,this.strokeDashArray),s.util.drawDashedLine(t,e+r,i,e+r,i+n,this.strokeDashArray),s.util.drawDashedLine(t,e+r,i+n,e,i+n,this.strokeDashArray),s.util.drawDashedLine(t,e,i+n,e,i,this.strokeDashArray),t.closePath()},toObject:function(t){return this.callSuper("toObject",["rx","ry"].concat(t))},toSVG:function(t){var e=this._createBaseSVGMarkup(),i=-this.width/2,r=-this.height/2;return e.push("\n"),t?t(e.join("")):e.join("")}}),s.Rect.ATTRIBUTE_NAMES=s.SHARED_ATTRIBUTES.concat("x y rx ry width height".split(" ")),s.Rect.fromElement=function(t,e,i){if(!t)return e(null);i=i||{};var r=s.parseAttributes(t,s.Rect.ATTRIBUTE_NAMES);r.left=r.left||0,r.top=r.top||0;var n=new s.Rect(o(i?s.util.object.clone(i):{},r));n.visible=n.visible&&0\n"),t?t(n.join("")):n.join("")},commonRender:function(t){var e,i=this.points.length,r=this.pathOffset.x,n=this.pathOffset.y;if(!i||isNaN(this.points[i-1].y))return!1;t.beginPath(),t.moveTo(this.points[0].x-r,this.points[0].y-n);for(var s=0;s"},toObject:function(t){return n(this.callSuper("toObject",t),{path:this.path.map(function(t){return t.slice()}),top:this.top,left:this.left})},toDatalessObject:function(t){var e=this.toObject(["sourcePath"].concat(t));return e.sourcePath&&delete e.path,e},toSVG:function(t){for(var e,i=[],r=this._createBaseSVGMarkup(),n=0,s=this.path.length;n\n"),t?t(r.join("")):r.join("")},complexity:function(){return this.path.length},_parsePath:function(){for(var t,e,i,r,n,s=[],o=[],a=/([-+]?((\d+\.\d+)|((\d+)|(\.\d+)))(?:e[-+]?\d+)?)/gi,h=0,c=this.path.length;hd)for(var p=1,v=n.length;p"},addWithUpdate:function(t){return this._restoreObjectsState(),c.util.resetObjectTransform(this),t&&(this._objects.push(t),t.group=this,t._set("canvas",this.canvas)),this._calcBounds(),this._updateObjectsCoords(),this.setCoords(),this.dirty=!0,this},removeWithUpdate:function(t){return this._restoreObjectsState(),c.util.resetObjectTransform(this),this.remove(t),this._calcBounds(),this._updateObjectsCoords(),this.setCoords(),this.dirty=!0,this},_onObjectAdded:function(t){this.dirty=!0,t.group=this,t._set("canvas",this.canvas)},_onObjectRemoved:function(t){this.dirty=!0,delete t.group},_set:function(t,e){var i=this._objects.length;if(this.useSetOnGroup)for(;i--;)this._objects[i].setOnGroup(t,e);if("canvas"===t)for(;i--;)this._objects[i]._set(t,e);c.Object.prototype._set.call(this,t,e)},toObject:function(r){var n=this.includeDefaultValues,t=this._objects.map(function(t){var e=t.includeDefaultValues;t.includeDefaultValues=n;var i=t.toObject(r);return t.includeDefaultValues=e,i}),e=c.Object.prototype.toObject.call(this,r);return e.objects=t,e},toDatalessObject:function(r){var t,e=this.sourcePath;if(e)t=e;else{var n=this.includeDefaultValues;t=this._objects.map(function(t){var e=t.includeDefaultValues;t.includeDefaultValues=n;var i=t.toDatalessObject(r);return t.includeDefaultValues=e,i})}var i=c.Object.prototype.toDatalessObject.call(this,r);return i.objects=t,i},render:function(t){this._transformDone=!0,this.callSuper("render",t),this._transformDone=!1},shouldCache:function(){var t=this.objectCaching&&(!this.group||this.needsItsOwnCache()||!this.group.isOnACache());if(this.ownCaching=t)for(var e=0,i=this._objects.length;e\n');for(var i=0,r=this._objects.length;i\n"),t?t(e.join("")):e.join("")}}),c.Group.fromObject=function(i,r){c.util.enlivenObjects(i.objects,function(t){var e=c.util.object.clone(i,!0);delete e.objects,r&&r(new c.Group(t,e,!0))})})}("undefined"!=typeof exports?exports:this),function(t){"use strict";var n=t.fabric||(t.fabric={});n.ActiveSelection||(n.ActiveSelection=n.util.createClass(n.Group,{type:"activeSelection",initialize:function(t,e){e=e||{},this._objects=t||[];for(var i=this._objects.length;i--;)this._objects[i].group=this;e.originX&&(this.originX=e.originX),e.originY&&(this.originY=e.originY),this._calcBounds(),this._updateObjectsCoords(),n.Object.prototype.initialize.call(this,e),this.setCoords()},toGroup:function(){var t=this._objects.concat();this._objects=[];var e=n.Object.prototype.toObject.call(this),i=new n.Group([]);if(delete e.type,i.set(e),t.forEach(function(t){t.canvas.remove(t),t.group=i}),i._objects=t,!this.canvas)return i;var r=this.canvas;return r.add(i),(r._activeObject=i).setCoords(),i},onDeselect:function(){return this.destroy(),!1},toString:function(){return"#"},shouldCache:function(){return!1},isOnACache:function(){return!1},_renderControls:function(t,e,i){t.save(),t.globalAlpha=this.isMoving?this.borderOpacityWhenMoving:1,this.callSuper("_renderControls",t,e),void 0===(i=i||{}).hasControls&&(i.hasControls=!1),void 0===i.hasRotatingPoint&&(i.hasRotatingPoint=!1),i.forActiveSelection=!0;for(var r=0,n=this._objects.length;r\n','\t\n',"\n"),n=' clip-path="url(#imageCrop_'+s+')" '}e.push('\n');var o=["\t\n"];if("fill"===this.paintFirst&&Array.prototype.push.apply(e,o),this.stroke||this.strokeDashArray){var a=this.fill;this.fill=null,e.push("\t\n'),this.fill=a}return"fill"!==this.paintFirst&&Array.prototype.push.apply(e,o),e.push("\n"),t?t(e.join("")):e.join("")},getSrc:function(t){var e=t?this._element:this._originalElement;return e?e.toDataURL?e.toDataURL():e.src:this.src||""},setSrc:function(t,e,i){return fabric.util.loadImage(t,function(t){this.setElement(t,i),this._setWidthHeight(),e(this)},this,i&&i.crossOrigin),this},toString:function(){return'#'},applyResizeFilters:function(){var t=this.resizeFilter,e=this.minimumScaleTrigger,i=this.getTotalObjectScaling(),r=i.scaleX,n=i.scaleY,s=this._filteredEl||this._originalElement;if(this.group&&this.set("dirty",!0),!t||e=t;for(var a=["highp","mediump","lowp"],h=0;h<3;h++)if(void 0,i="precision "+a[h]+" float;\nvoid main(){}",r=(e=s).createShader(e.FRAGMENT_SHADER),e.shaderSource(r,i),e.compileShader(r),e.getShaderParameter(r,e.COMPILE_STATUS)){fabric.webGlPrecision=a[h];break}}return this.isSupported=o},(fabric.WebglFilterBackend=t).prototype={tileSize:2048,resources:{},setupGLContext:function(t,e){this.dispose(),this.createWebGLCanvas(t,e),this.aPosition=new Float32Array([0,0,0,1,1,0,1,1]),this.chooseFastestCopyGLTo2DMethod(t,e)},chooseFastestCopyGLTo2DMethod:function(t,e){var i,r=void 0!==window.performance;try{new ImageData(1,1),i=!0}catch(t){i=!1}var n="undefined"!=typeof ArrayBuffer,s="undefined"!=typeof Uint8ClampedArray;if(r&&i&&n&&s){var o,a,h=fabric.util.createCanvasElement(),c=new ArrayBuffer(t*e*4),l={imageBuffer:c,destinationWidth:t,destinationHeight:e,targetCanvas:h};h.width=t,h.height=e,o=window.performance.now(),copyGLTo2DDrawImage.call(l,this.gl,l),a=window.performance.now()-o,o=window.performance.now(),copyGLTo2DPutImageData.call(l,this.gl,l),window.performance.now()-o 0.0) {\n"+this.fragmentSource[t]+"}\n}"},retrieveShader:function(t){var e,i=this.type+"_"+this.mode;return t.programCache.hasOwnProperty(i)||(e=this.buildSource(this.mode),t.programCache[i]=this.createProgram(t.context,e)),t.programCache[i]},applyTo2d:function(t){var e,i,r,n,s,o,a,h=t.imageData.data,c=h.length,l=1-this.alpha;e=(a=new f.Color(this.color).getSource())[0]*this.alpha,i=a[1]*this.alpha,r=a[2]*this.alpha;for(var u=0;u'},_getCacheCanvasDimensions:function(){var t=this.callSuper("_getCacheCanvasDimensions"),e=this.fontSize;return t.width+=e*t.zoomX,t.height+=e*t.zoomY,t},_render:function(t){this._setTextStyles(t),this._renderTextLinesBackground(t),this._renderTextDecoration(t,"underline"),this._renderText(t),this._renderTextDecoration(t,"overline"),this._renderTextDecoration(t,"linethrough")},_renderText:function(t){"stroke"===this.paintFirst?(this._renderTextStroke(t),this._renderTextFill(t)):(this._renderTextFill(t),this._renderTextStroke(t))},_setTextStyles:function(t,e,i){t.textBaseline="alphabetic",t.font=this._getFontDeclaration(e,i)},calcTextWidth:function(){for(var t=this.getLineWidth(0),e=1,i=this._textLines.length;ethis.__selectionStartOnMouseDown?(this.selectionStart=this.__selectionStartOnMouseDown,this.selectionEnd=e):(this.selectionStart=e,this.selectionEnd=this.__selectionStartOnMouseDown),this.selectionStart===i&&this.selectionEnd===r||(this.restartCursorIfNeeded(),this._fireSelectionChanged(),this._updateTextarea(),this.renderCursorOrSelection()))}},_setEditingProps:function(){this.hoverCursor="text",this.canvas&&(this.canvas.defaultCursor=this.canvas.moveCursor="text"),this.borderColor=this.editingBorderColor,this.hasControls=this.selectable=!1,this.lockMovementX=this.lockMovementY=!0},fromStringToGraphemeSelection:function(t,e,i){var r=i.slice(0,t),n=fabric.util.string.graphemeSplit(r).length;if(t===e)return{selectionStart:n,selectionEnd:n};var s=i.slice(t,e);return{selectionStart:n,selectionEnd:n+fabric.util.string.graphemeSplit(s).length}},fromGraphemeToStringSelection:function(t,e,i){var r=i.slice(0,t).join("").length;return t===e?{selectionStart:r,selectionEnd:r}:{selectionStart:r,selectionEnd:r+i.slice(t,e).join("").length}},_updateTextarea:function(){if(this.cursorOffsetCache={},this.hiddenTextarea){if(!this.inCompositionMode){var t=this.fromGraphemeToStringSelection(this.selectionStart,this.selectionEnd,this._text);this.hiddenTextarea.selectionStart=t.selectionStart,this.hiddenTextarea.selectionEnd=t.selectionEnd}this.updateTextareaPosition()}},updateFromTextArea:function(){if(this.hiddenTextarea){this.cursorOffsetCache={},this.text=this.hiddenTextarea.value,this._shouldClearDimensionCache()&&(this.initDimensions(),this.setCoords());var t=this.fromStringToGraphemeSelection(this.hiddenTextarea.selectionStart,this.hiddenTextarea.selectionEnd,this.hiddenTextarea.value);this.selectionEnd=this.selectionStart=t.selectionEnd,this.inCompositionMode||(this.selectionStart=t.selectionStart),this.updateTextareaPosition()}},updateTextareaPosition:function(){if(this.selectionStart===this.selectionEnd){var t=this._calcTextareaPosition();this.hiddenTextarea.style.left=t.left,this.hiddenTextarea.style.top=t.top}},_calcTextareaPosition:function(){if(!this.canvas)return{x:1,y:1};var t=this.inCompositionMode?this.compositionStart:this.selectionStart,e=this._getCursorBoundaries(t),i=this.get2DCursorLocation(t),r=i.lineIndex,n=i.charIndex,s=this.getValueOfPropertyAt(r,n,"fontSize")*this.lineHeight,o=e.leftOffset,a=this.calcTransformMatrix(),h={x:e.left+o,y:e.top+e.topOffset+s},c=this.canvas.upperCanvasEl,l=c.width,u=c.height,f=l-s,d=u-s,g=c.clientWidth/l,p=c.clientHeight/u;return h=fabric.util.transformPoint(h,a),(h=fabric.util.transformPoint(h,this.canvas.viewportTransform)).x*=g,h.y*=p,h.x<0&&(h.x=0),h.x>f&&(h.x=f),h.y<0&&(h.y=0),h.y>d&&(h.y=d),h.x+=this.canvas._offset.left,h.y+=this.canvas._offset.top,{left:h.x+"px",top:h.y+"px",fontSize:s+"px",charHeight:s}},_saveEditingProps:function(){this._savedProps={hasControls:this.hasControls,borderColor:this.borderColor,lockMovementX:this.lockMovementX,lockMovementY:this.lockMovementY,hoverCursor:this.hoverCursor,defaultCursor:this.canvas&&this.canvas.defaultCursor,moveCursor:this.canvas&&this.canvas.moveCursor}},_restoreEditingProps:function(){this._savedProps&&(this.hoverCursor=this._savedProps.hoverCursor,this.hasControls=this._savedProps.hasControls,this.borderColor=this._savedProps.borderColor,this.lockMovementX=this._savedProps.lockMovementX,this.lockMovementY=this._savedProps.lockMovementY,this.canvas&&(this.canvas.defaultCursor=this._savedProps.defaultCursor,this.canvas.moveCursor=this._savedProps.moveCursor))},exitEditing:function(){var t=this._textBeforeEdit!==this.text;return this.selected=!1,this.isEditing=!1,this.selectable=!0,this.selectionEnd=this.selectionStart,this.hiddenTextarea&&(this.hiddenTextarea.blur&&this.hiddenTextarea.blur(),this.canvas&&this.hiddenTextarea.parentNode.removeChild(this.hiddenTextarea),this.hiddenTextarea=null),this.abortCursorAnimation(),this._restoreEditingProps(),this._currentCursorOpacity=0,this._shouldClearDimensionCache()&&(this.initDimensions(),this.setCoords()),this.fire("editing:exited"),t&&this.fire("modified"),this.canvas&&(this.canvas.off("mouse:move",this.mouseMoveHandler),this.canvas.fire("text:editing:exited",{target:this}),t&&this.canvas.fire("object:modified",{target:this})),this},_removeExtraneousStyles:function(){for(var t in this.styles)this._textLines[t]||delete this.styles[t]},removeStyleFromTo:function(t,e){var i,r,n=this.get2DCursorLocation(t,!0),s=this.get2DCursorLocation(e,!0),o=n.lineIndex,a=n.charIndex,h=s.lineIndex,c=s.charIndex;if(o!==h){if(this.styles[o])for(i=a;it?this.selectionStart=t:this.selectionStart<0&&(this.selectionStart=0),this.selectionEnd>t?this.selectionEnd=t:this.selectionEnd<0&&(this.selectionEnd=0)}})}(),fabric.util.object.extend(fabric.IText.prototype,{initDoubleClickSimulation:function(){this.__lastClickTime=+new Date,this.__lastLastClickTime=+new Date,this.__lastPointer={},this.on("mousedown",this.onMouseDown)},onMouseDown:function(t){if(this.canvas){this.__newClickTime=+new Date;var e=t.pointer;this.isTripleClick(e)&&(this.fire("tripleclick",t),this._stopEvent(t.e)),this.__lastLastClickTime=this.__lastClickTime,this.__lastClickTime=this.__newClickTime,this.__lastPointer=e,this.__lastIsEditing=this.isEditing,this.__lastSelected=this.selected}},isTripleClick:function(t){return this.__newClickTime-this.__lastClickTime<500&&this.__lastClickTime-this.__lastLastClickTime<500&&this.__lastPointer.x===t.x&&this.__lastPointer.y===t.y},_stopEvent:function(t){t.preventDefault&&t.preventDefault(),t.stopPropagation&&t.stopPropagation()},initCursorSelectionHandlers:function(){this.initMousedownHandler(),this.initMouseupHandler(),this.initClicks()},initClicks:function(){this.on("mousedblclick",function(t){this.selectWord(this.getSelectionStartFromPointer(t.e))}),this.on("tripleclick",function(t){this.selectLine(this.getSelectionStartFromPointer(t.e))})},_mouseDownHandler:function(t){!this.canvas||!this.editable||t.e.button&&1!==t.e.button||(this.__isMousedown=!0,this.selected&&this.setCursorByClick(t.e),this.isEditing&&(this.__selectionStartOnMouseDown=this.selectionStart,this.selectionStart===this.selectionEnd&&this.abortCursorAnimation(),this.renderCursorOrSelection()))},_mouseDownHandlerBefore:function(t){!this.canvas||!this.editable||t.e.button&&1!==t.e.button||this===this.canvas._activeObject&&(this.selected=!0)},initMousedownHandler:function(){this.on("mousedown",this._mouseDownHandler),this.on("mousedown:before",this._mouseDownHandlerBefore)},initMouseupHandler:function(){this.on("mouseup",this.mouseUpHandler)},mouseUpHandler:function(t){if(this.__isMousedown=!1,!(!this.editable||this.group||t.transform&&t.transform.actionPerformed||t.e.button&&1!==t.e.button)){if(this.canvas){var e=this.canvas._activeObject;if(e&&e!==this)return}this.__lastSelected&&!this.__corner?(this.selected=!1,this.__lastSelected=!1,this.enterEditing(t.e),this.selectionStart===this.selectionEnd?this.initDelayedCursor(!0):this.renderCursorOrSelection()):this.selected=!0}},setCursorByClick:function(t){var e=this.getSelectionStartFromPointer(t),i=this.selectionStart,r=this.selectionEnd;t.shiftKey?this.setSelectionStartEndWithShift(i,r,e):(this.selectionStart=e,this.selectionEnd=e),this.isEditing&&(this._fireSelectionChanged(),this._updateTextarea())},getSelectionStartFromPointer:function(t){for(var e=this.getLocalPointer(t),i=0,r=0,n=0,s=0,o=0,a=0,h=this._textLines.length;athis._text.length&&(a=this._text.length),a}}),fabric.util.object.extend(fabric.IText.prototype,{initHiddenTextarea:function(){this.hiddenTextarea=fabric.document.createElement("textarea"),this.hiddenTextarea.setAttribute("autocapitalize","off"),this.hiddenTextarea.setAttribute("autocorrect","off"),this.hiddenTextarea.setAttribute("autocomplete","off"),this.hiddenTextarea.setAttribute("spellcheck","false"),this.hiddenTextarea.setAttribute("data-fabric-hiddentextarea",""),this.hiddenTextarea.setAttribute("wrap","off");var t=this._calcTextareaPosition();this.hiddenTextarea.style.cssText="position: absolute; top: "+t.top+"; left: "+t.left+"; z-index: -999; opacity: 0; width: 1px; height: 1px; font-size: 1px; paddingï½°top: "+t.fontSize+";",fabric.document.body.appendChild(this.hiddenTextarea),fabric.util.addListener(this.hiddenTextarea,"keydown",this.onKeyDown.bind(this)),fabric.util.addListener(this.hiddenTextarea,"keyup",this.onKeyUp.bind(this)),fabric.util.addListener(this.hiddenTextarea,"input",this.onInput.bind(this)),fabric.util.addListener(this.hiddenTextarea,"copy",this.copy.bind(this)),fabric.util.addListener(this.hiddenTextarea,"cut",this.copy.bind(this)),fabric.util.addListener(this.hiddenTextarea,"paste",this.paste.bind(this)),fabric.util.addListener(this.hiddenTextarea,"compositionstart",this.onCompositionStart.bind(this)),fabric.util.addListener(this.hiddenTextarea,"compositionupdate",this.onCompositionUpdate.bind(this)),fabric.util.addListener(this.hiddenTextarea,"compositionend",this.onCompositionEnd.bind(this)),!this._clickHandlerInitialized&&this.canvas&&(fabric.util.addListener(this.canvas.upperCanvasEl,"click",this.onClick.bind(this)),this._clickHandlerInitialized=!0)},keysMap:{9:"exitEditing",27:"exitEditing",33:"moveCursorUp",34:"moveCursorDown",35:"moveCursorRight",36:"moveCursorLeft",37:"moveCursorLeft",38:"moveCursorUp",39:"moveCursorRight",40:"moveCursorDown"},ctrlKeysMapUp:{67:"copy",88:"cut"},ctrlKeysMapDown:{65:"selectAll"},onClick:function(){this.hiddenTextarea&&this.hiddenTextarea.focus()},onKeyDown:function(t){if(this.isEditing&&!this.inCompositionMode){if(t.keyCode in this.keysMap)this[this.keysMap[t.keyCode]](t);else{if(!(t.keyCode in this.ctrlKeysMapDown&&(t.ctrlKey||t.metaKey)))return;this[this.ctrlKeysMapDown[t.keyCode]](t)}t.stopImmediatePropagation(),t.preventDefault(),33<=t.keyCode&&t.keyCode<=40?(this.clearContextTop(),this.renderCursorOrSelection()):this.canvas&&this.canvas.requestRenderAll()}},onKeyUp:function(t){!this.isEditing||this._copyDone||this.inCompositionMode?this._copyDone=!1:t.keyCode in this.ctrlKeysMapUp&&(t.ctrlKey||t.metaKey)&&(this[this.ctrlKeysMapUp[t.keyCode]](t),t.stopImmediatePropagation(),t.preventDefault(),this.canvas&&this.canvas.requestRenderAll())},onInput:function(t){var e=this.fromPaste;if(this.fromPaste=!1,t&&t.stopPropagation(),this.isEditing){var i,r,n=this._splitTextIntoLines(this.hiddenTextarea.value).graphemeText,s=this._text.length,o=n.length,a=o-s;if(""===this.hiddenTextarea.value)return this.styles={},this.updateFromTextArea(),this.fire("changed"),void(this.canvas&&(this.canvas.fire("text:changed",{target:this}),this.canvas.requestRenderAll()));var h=this.fromStringToGraphemeSelection(this.hiddenTextarea.selectionStart,this.hiddenTextarea.selectionEnd,this.hiddenTextarea.value),c=this.selectionStart>h.selectionStart;this.selectionStart!==this.selectionEnd?(i=this._text.slice(this.selectionStart,this.selectionEnd),a+=this.selectionEnd-this.selectionStart):o=this._text.length&&this.selectionEnd>=this._text.length||this._moveCursorUpOrDown("Down",t)},moveCursorUp:function(t){0===this.selectionStart&&0===this.selectionEnd||this._moveCursorUpOrDown("Up",t)},_moveCursorUpOrDown:function(t,e){var i=this["get"+t+"CursorOffset"](e,"right"===this._selectionDirection);e.shiftKey?this.moveCursorWithShift(i):this.moveCursorWithoutShift(i),0!==i&&(this.setSelectionInBoundaries(),this.abortCursorAnimation(),this._currentCursorOpacity=1,this.initDelayedCursor(),this._fireSelectionChanged(),this._updateTextarea())},moveCursorWithShift:function(t){var e="left"===this._selectionDirection?this.selectionStart+t:this.selectionEnd+t;return this.setSelectionStartEndWithShift(this.selectionStart,this.selectionEnd,e),0!==t},moveCursorWithoutShift:function(t){return t<0?(this.selectionStart+=t,this.selectionEnd=this.selectionStart):(this.selectionEnd+=t,this.selectionStart=this.selectionEnd),0!==t},moveCursorLeft:function(t){0===this.selectionStart&&0===this.selectionEnd||this._moveCursorLeftOrRight("Left",t)},_move:function(t,e,i){var r;if(t.altKey)r=this["findWordBoundary"+i](this[e]);else{if(!t.metaKey&&35!==t.keyCode&&36!==t.keyCode)return this[e]+="Left"===i?-1:1,!0;r=this["findLineBoundary"+i](this[e])}if(void 0!==typeof r&&this[e]!==r)return this[e]=r,!0},_moveLeft:function(t,e){return this._move(t,e,"Left")},_moveRight:function(t,e){return this._move(t,e,"Right")},moveCursorLeftWithoutShift:function(t){var e=!0;return this._selectionDirection="left",this.selectionEnd===this.selectionStart&&0!==this.selectionStart&&(e=this._moveLeft(t,"selectionStart")),this.selectionEnd=this.selectionStart,e},moveCursorLeftWithShift:function(t){return"right"===this._selectionDirection&&this.selectionStart!==this.selectionEnd?this._moveLeft(t,"selectionEnd"):0!==this.selectionStart?(this._selectionDirection="left",this._moveLeft(t,"selectionStart")):void 0},moveCursorRight:function(t){this.selectionStart>=this._text.length&&this.selectionEnd>=this._text.length||this._moveCursorLeftOrRight("Right",t)},_moveCursorLeftOrRight:function(t,e){var i="moveCursor"+t+"With";this._currentCursorOpacity=1,e.shiftKey?i+="Shift":i+="outShift",this[i](e)&&(this.abortCursorAnimation(),this.initDelayedCursor(),this._fireSelectionChanged(),this._updateTextarea())},moveCursorRightWithShift:function(t){return"left"===this._selectionDirection&&this.selectionStart!==this.selectionEnd?this._moveRight(t,"selectionStart"):this.selectionEnd!==this._text.length?(this._selectionDirection="right",this._moveRight(t,"selectionEnd")):void 0},moveCursorRightWithoutShift:function(t){var e=!0;return this._selectionDirection="right",this.selectionStart===this.selectionEnd?(e=this._moveRight(t,"selectionStart"),this.selectionEnd=this.selectionStart):this.selectionStart=this.selectionEnd,e},removeChars:function(t,e){void 0===e&&(e=t+1),this.removeStyleFromTo(t,e),this._text.splice(t,e-t),this.text=this._text.join(""),this.set("dirty",!0),this._shouldClearDimensionCache()&&(this.initDimensions(),this.setCoords()),this._removeExtraneousStyles()},insertChars:function(t,e,i,r){void 0===r&&(r=i),i\n",e.textBgRects.join(""),'\t\t",e.textSpans.join(""),"\n","\t\n")},_getSVGTextAndBg:function(t,e){var i,r=[],n=[],s=t;this._setSVGBg(n);for(var o=0,a=this._textLines.length;o",fabric.util.string.escapeXml(t),""].join("")},_setSVGTextLineText:function(t,e,i,r){var n,s,o,a,h,c=this.getHeightOfLine(e),l=-1!==this.textAlign.indexOf("justify"),u="",f=0,d=this._textLines[e];r+=c*(1-this._fontSizeFraction)/this.lineHeight;for(var g=0,p=d.length-1;g<=p;g++)h=g===p||this.charSpacing,u+=d[g],o=this.__charBounds[e][g],0===f?(i+=o.kernedWidth-o.width,f+=o.width):f+=o.kernedWidth,l&&!h&&this._reSpaceAndTab.test(d[g])&&(h=!0),h||(n=n||this.getCompleteStyleDeclaration(e,g),s=this.getCompleteStyleDeclaration(e,g+1),h=this._hasStyleChangedForSvg(n,s)),h&&(a=this._getStyleDeclaration(e,g)||{},t.push(this._createTextCharSpan(u,a,i,r)),u="",n=s,i+=f,f=0)},_pushTextBgRect:function(t,e,i,r,n,s){var o=fabric.Object.NUM_FRACTION_DIGITS;t.push("\t\t\n')},_setSVGTextLineBg:function(t,e,i,r){for(var n,s,o=this._textLines[e],a=this.getHeightOfLine(e)/this.lineHeight,h=0,c=0,l=this.getValueOfPropertyAt(e,0,"textBackgroundColor"),u=0,f=o.length;uthis.width&&this._set("width",this.dynamicMinWidth),-1!==this.textAlign.indexOf("justify")&&this.enlargeSpaces(),this.height=this.calcTextHeight(),this.saveState({propertySet:"_dimensionAffectingProps"}))},_generateStyleMap:function(t){for(var e=0,i=0,r=0,n={},s=0;sthis.dynamicMinWidth&&(this.dynamicMinWidth=f-g+r),s},isEndOfWrapping:function(t){return!this._styleMap[t+1]||this._styleMap[t+1].line!==this._styleMap[t].line},_splitTextIntoLines:function(t){for(var e=v.Text.prototype._splitTextIntoLines.call(this,t),i=this._wrapText(e.lines,this.width),r=new Array(i.length),n=0;n=a.getMinWidth()?(a.set("width",c),!0):void 0},fabric.util.object.extend(fabric.Textbox.prototype,{_removeExtraneousStyles:function(){for(var t in this._styleMap)this._textLines[t]||delete this.styles[this._styleMap[t].line]}})}(); diff --git a/static/scripts/frontpage.js b/static/scripts/frontpage.js deleted file mode 100644 index 66f36fce..00000000 --- a/static/scripts/frontpage.js +++ /dev/null @@ -1,130 +0,0 @@ -//checkForGCodeUpdate(); - -//setInterval(function(){ alert("Hello"); }, 3000); - -var scale = 1; - -var draw = SVG('workarea').size('100%','100%').panZoom({zoomMin: 1, zoomMax: 500, zoomFactor:2.5}); -var viewbox = draw.viewbox(); -var originX = viewbox.width/2; -var originY = viewbox.height/2; -var currentPosX = 0; -var currentPosY = 0; -var gcode = null; -//var rect = draw.rect(100,100).attr({fill: '#f06'}) -//var sheet = draw.image('/static/images/materials/Plywood_texture.JPG',96,48).center(originX,originY) - -var gridLines = draw.group() -gridLines.add(draw.line(0*scale,0*scale,96*scale,0*scale).stroke({width:.1, color: '#000'})) -gridLines.add(draw.line(0*scale,48*scale,96*scale,48*scale).stroke({width:.1, color: '#000'})) -gridLines.add(draw.line(0*scale,24*scale,96*scale,24*scale).stroke({width:.1, color: '#000'})) -gridLines.add(draw.line(0*scale,0*scale,0*scale,48*scale).stroke({width:.1, color: '#000'})) -gridLines.add(draw.line(24*scale,0*scale,24*scale,48*scale).stroke({width:.1, color: '#000'})) -gridLines.add(draw.line(48*scale,0*scale,48*scale,48*scale).stroke({width:.1, color: '#000'})) -gridLines.add(draw.line(72*scale,0*scale,72*scale,48*scale).stroke({width:.1, color: '#000'})) -gridLines.add(draw.line(96*scale,0*scale,96*scale,48*scale).stroke({width:.1, color: '#000'})) -gridLines.center(originX,originY) -//gridLines.scale(scale,scale) - -var sled = draw.group() -sled.add(draw.line(1.5*scale,-0.0*scale,1.5*scale,3.0*scale).stroke({width:.1,color:"#F00"})) -sled.add(draw.line(-0.0*scale,1.5*scale,3.0*scale,1.5*scale).stroke({width:.1,color:"#F00"})) -sled.add(draw.circle(3*scale).stroke({width:.1,color:"#F00"}).fill({color:"#fff",opacity:0})) -sled.center(originX,originY) -//sled.center(vx,vy) -draw.zoom(10, {x:originX,y:originY}); - -function positionUpdate(x,y,z){ - var _x, _y =0 - //console.log(x) - if ($("#units").text()=="MM"){ - _x = originX+x*scale/25.4 - _y = originY-y*scale/25.4 - } - else{ - _x = originX+x*scale; - _y = originY-y*scale - } - - sled.center(_x, _y); -} - -function unitSwitch(){ - if ( $("#units").text()=="MM") { - $("#units").text("INCHES"); - distToMove = Math.round($("#distToMove").val()/25.4,3) - $("#distToMove").val(distToMove); - updateSetting('toInches',distToMove); - } else { - $("#units").text("MM"); - distToMove = Math.round($("#distToMove").val()*25.4,3) - $("#distToMove").val(distToMove); - updateSetting('toMM',distToMove); - } -} - -$(document).ready(function(){ - settingRequest("units"); - settingRequest("distToMove"); - checkForGCodeUpdate(); -}); - -function pauseRun(){ - if ($("#pauseButton").text()=="Pause"){ - action('pauseRun'); - } - else { - action('resumeRun'); - } -} - -function processRequestedSetting(msg){ - console.log(msg); - if (msg.setting=="pauseButtonSetting"){ - $("#pauseButton").text(msg.value); - } - if (msg.setting=="units"){ - console.log("requestedSetting:"+msg.value); - $("#units").text(msg.value) - } - if (msg.setting=="distToMove"){ - console.log("requestedSetting for distToMove:"+msg.value); - $("#distToMove").val(msg.value) - } - if (msg.setting=="unitsZ"){ - console.log("requestedSetting:"+msg.value); - $("#unitsZ").text(msg.value) - } - if (msg.setting=="distToMoveZ"){ - console.log("requestedSetting for distToMoveZ:"+msg.value); - $("#distToMoveZ").val(msg.value) - } -} - -function processPositionMessage(msg){ - var json = JSON.parse(msg.data); - $('#positionMessage').html('

XPos:'+json.xval+' Ypos:'+json.yval+' ZPos:'+json.zval+'

'); - positionUpdate(json.xval,json.yval,json.zval); -} - -function gcodeUpdate(msg){ - console.log("updating gcode"); - if (gcode!=null) { - console.log("removing gcode"); - //gcode.remove(); - gcode.remove(); - } - gcode = draw.group(); - var data = JSON.parse(msg.data) - data.forEach(function(line) { - console.log(line) - if (line.type=='line'){ - if (line.dashed==true) { - gcode.add(draw.polyline(line.points).fill('none').stroke({width:.1, color: '#AA0'})) - } else { - gcode.add(draw.polyline(line.points).fill('none').stroke({width:.1, color: '#00F'})) - } - } - gcode.move(originX,originY) - }); -} diff --git a/static/scripts/frontpage3d.js b/static/scripts/frontpage3d.js new file mode 100644 index 00000000..7491e3e8 --- /dev/null +++ b/static/scripts/frontpage3d.js @@ -0,0 +1,809 @@ +//checkForGCodeUpdate(); +//checkForGCodeUpdate(); + +//setInterval(function(){ alert("Hello"); }, 3000); + +var cutSquareGroup = new THREE.Group(); +var showBoard = false; +var showLabels = false; +var homeX = 0; +var homeY = 0; + +var renderer = new THREE.WebGLRenderer(); +var w = $("#workarea").width();//-20; +var h = $("#workarea").height();//-20; +renderer.setSize( w, h ); +//console.log("w="+w+", h="+h); + +container = document.getElementById('workarea'); +container.appendChild(renderer.domElement); +var imageShowing = 1 + +var gcode = new THREE.Group(); +var textLabels = new THREE.Group(); +//var cutTrailGroup = new THREE.Group(); + +var cameraPerspective = 0; // 0 = Orthographic, 1 = Perspective +var scale = .07 +var cameraO; +var cameraP; + +var cameraO = new THREE.OrthographicCamera(w/-2*scale, w/2*scale, h/2*scale, h/-2*scale, 1, 100*500/380); +cameraO.position.set(0, 0, 100); //380 +cameraO.lookAt(0,0,0); +var cameraP = new THREE.PerspectiveCamera(45, w/h, 1, 500); +cameraP.position.set(0, 0, 100); +cameraP.lookAt(0,0,0); + + +//setCameraPerspective(true); // true indicates initial setting +var controlsO = new THREE.OrbitControls(cameraO, renderer.domElement); +var controlsP = new THREE.OrbitControls(cameraP, renderer.domElement); +controlsO.screenSpacePanning = true; +controlsP.screenSpacePanning = true; + +var view3D = true; +toggle3DView(); // makes it not true and applies appropriate settings +//controls.update(); +controlsO.saveState(); +controlsP.saveState(); + +var scene = new THREE.Scene(); +scene.background= new THREE.Color(0xeeeeee); +var light = new THREE.AmbientLight( 0x404040 ); // soft white light +scene.add( light ); +var blueLineMaterial = new THREE.LineBasicMaterial( {color:0x0000ff }); +var lightBlueLineMaterial = new THREE.LineBasicMaterial( {color:0xadd8e6 }); +var greenLineMaterial = new THREE.LineBasicMaterial( {color:0x00aa00 }); +var redLineMaterial = new THREE.LineBasicMaterial( {color:0xff0000 }); +var blackLineMaterial = new THREE.LineBasicMaterial( {color:0x000000 }); +var grayLineMaterial = new THREE.LineBasicMaterial( {color:0x777777 }); + +var greenLineDashedMaterial = new THREE.LineDashedMaterial( {color:0x00aa00, dashSize:.1, gapSize: .1} ); +var blackDashedMaterial = new THREE.LineDashedMaterial( {color:0x000000, dashSize:.5, gapSize: .5} ); + +var outerFrameShape = new THREE.Geometry(); +outerFrameShape.vertices.push(new THREE.Vector3(-48, 24, 0)); +outerFrameShape.vertices.push(new THREE.Vector3(48, 24, 0)); +outerFrameShape.vertices.push(new THREE.Vector3(48, -24, 0)); +outerFrameShape.vertices.push(new THREE.Vector3(-48, -24, 0)); +outerFrameShape.vertices.push(new THREE.Vector3(-48, 24, 0)); +var outerFrame = new THREE.Line(outerFrameShape, blackLineMaterial); + +var frameLineSegments = new THREE.Geometry(); +frameLineSegments.vertices.push(new THREE.Vector3(-24, 24, 0)); +frameLineSegments.vertices.push(new THREE.Vector3(-24, -24, 0)); +frameLineSegments.vertices.push(new THREE.Vector3(0, 24, 0)); +frameLineSegments.vertices.push(new THREE.Vector3(0, -24, 0)); +frameLineSegments.vertices.push(new THREE.Vector3(24, 24, 0)); +frameLineSegments.vertices.push(new THREE.Vector3(24, -24, 0)); +frameLineSegments.vertices.push(new THREE.Vector3(-48, 0, 0)); +frameLineSegments.vertices.push(new THREE.Vector3(48, 0, 0)); +var innerFrame = new THREE.LineSegments(frameLineSegments, blackDashedMaterial) +innerFrame.computeLineDistances(); + +scene.add(outerFrame); +scene.add(innerFrame); + + +var sledHorizontalLineSegments = new THREE.Geometry(); +sledHorizontalLineSegments.vertices.push(new THREE.Vector3(-1.5, 0, 0)); +sledHorizontalLineSegments.vertices.push(new THREE.Vector3(1.5, 0, 0)); +var sledHorizontalLine = new THREE.LineSegments(sledHorizontalLineSegments, redLineMaterial); + +var sledVerticalLineSegments = new THREE.Geometry(); +sledVerticalLineSegments.vertices.push(new THREE.Vector3(0, -1.5, 0)); +sledVerticalLineSegments.vertices.push(new THREE.Vector3(0, 1.5, 0)); +var sledVerticalLine = new THREE.LineSegments(sledVerticalLineSegments, redLineMaterial); + +var sledCircleGeometry = new THREE.CircleGeometry(1,32); +var sledCircleEdges = new THREE.EdgesGeometry(sledCircleGeometry) +var sledCircle = new THREE.LineSegments(sledCircleEdges,redLineMaterial); + +var sled = new THREE.Group(); +sled.add(sledHorizontalLine); +sled.add(sledVerticalLine); +sled.add(sledCircle); +sled.position.set(0,0,0); + + +var homeHorizontalLineSegments = new THREE.Geometry(); +homeHorizontalLineSegments.vertices.push(new THREE.Vector3(-1.25, 0, 0)); +homeHorizontalLineSegments.vertices.push(new THREE.Vector3(1.25, 0, 0)); +var homeHorizontalLine = new THREE.LineSegments(homeHorizontalLineSegments, greenLineMaterial); + +var homeVerticalLineSegments = new THREE.Geometry(); +homeVerticalLineSegments.vertices.push(new THREE.Vector3(0, -1.25, 0)); +homeVerticalLineSegments.vertices.push(new THREE.Vector3(0, 1.25, 0)); +var homeVerticalLine = new THREE.LineSegments(homeVerticalLineSegments, greenLineMaterial); + +var homeCircleGeometry = new THREE.CircleGeometry(.75,32); +var homeCircleEdges = new THREE.EdgesGeometry(homeCircleGeometry) +var homeCircle = new THREE.LineSegments(homeCircleEdges,greenLineMaterial); + +var home = new THREE.Group(); +home.add(homeHorizontalLine); +home.add(homeVerticalLine); +home.add(homeCircle); +home.position.set(0,0,0); + + +var gcodePosHorizontalLineSegments = new THREE.Geometry(); +gcodePosHorizontalLineSegments.vertices.push(new THREE.Vector3(-1.0, 0, 0)); +gcodePosHorizontalLineSegments.vertices.push(new THREE.Vector3(1.0, 0, 0)); +var gcodePosHorizontalLine = new THREE.LineSegments(gcodePosHorizontalLineSegments, blackLineMaterial); + +var gcodePosVerticalLineSegments = new THREE.Geometry(); +gcodePosVerticalLineSegments.vertices.push(new THREE.Vector3(0, -1.0, 0)); +gcodePosVerticalLineSegments.vertices.push(new THREE.Vector3(0, 1.0, 0)); +var gcodePosVerticalLine = new THREE.LineSegments(gcodePosVerticalLineSegments, blackLineMaterial); + +var gcodePosCircleGeometry = new THREE.CircleGeometry(.5,32); +var gcodePosCircleEdges = new THREE.EdgesGeometry(gcodePosCircleGeometry) +var gcodePosCircle = new THREE.LineSegments(gcodePosCircleEdges,blackLineMaterial); + +var gcodePos = new THREE.Group(); +gcodePos.add(gcodePosHorizontalLine); +gcodePos.add(gcodePosVerticalLine); +gcodePos.add(gcodePosCircle); +gcodePos.position.set(0,0,0); + +var computedSledHorizontalLineSegments = new THREE.Geometry(); +computedSledHorizontalLineSegments.vertices.push(new THREE.Vector3(-1.5, 0, 0)); +computedSledHorizontalLineSegments.vertices.push(new THREE.Vector3(1.5, 0, 0)); +var computedSledHorizontalLine = new THREE.LineSegments(computedSledHorizontalLineSegments, grayLineMaterial); + +var computedSledVerticalLineSegments = new THREE.Geometry(); +computedSledVerticalLineSegments.vertices.push(new THREE.Vector3(0, -1.5, 0)); +computedSledVerticalLineSegments.vertices.push(new THREE.Vector3(0, 1.5, 0)); +var computedSledVerticalLine = new THREE.LineSegments(computedSledVerticalLineSegments, grayLineMaterial); + +var computedSledCircleGeometry = new THREE.CircleGeometry(1,32); +var computedSledCircleEdges = new THREE.EdgesGeometry(computedSledCircleGeometry) +var computedSledCircle = new THREE.LineSegments(computedSledCircleEdges,grayLineMaterial); + +var computedSled = new THREE.Group(); +computedSled.add(computedSledHorizontalLine); +computedSled.add(computedSledVerticalLine); +computedSled.add(computedSledCircle); +computedSled.position.set(0,0,0); + +var cursorHorizontalLineSegments = new THREE.Geometry(); +cursorHorizontalLineSegments.vertices.push(new THREE.Vector3(-1.5, 0, 0)); +cursorHorizontalLineSegments.vertices.push(new THREE.Vector3(1.5, 0, 0)); +var cursorHorizontalLine = new THREE.LineSegments(cursorHorizontalLineSegments, blueLineMaterial); + +var cursorVerticalLineSegments = new THREE.Geometry(); +cursorVerticalLineSegments.vertices.push(new THREE.Vector3(0, -1.5, 0)); +cursorVerticalLineSegments.vertices.push(new THREE.Vector3(0, 1.5, 0)); +var cursorVerticalLine = new THREE.LineSegments(cursorVerticalLineSegments, blueLineMaterial); + +var cursorCircleGeometry = new THREE.CircleGeometry(1,32); +var cursorCircleEdges = new THREE.EdgesGeometry(cursorCircleGeometry) +var cursorCircle = new THREE.LineSegments(cursorCircleEdges,blueLineMaterial); + +var cursor = new THREE.Group(); +cursor.add(cursorHorizontalLine); +cursor.add(cursorVerticalLine); +cursor.add(cursorCircle); +cursor.position.set(0,0,0); + + +var cursorVLineGeometry = new THREE.BufferGeometry(); +var cursorVLinePositions = new Float32Array(2*3); +cursorVLineGeometry.addAttribute( 'position', new THREE.BufferAttribute(cursorVLinePositions, 3)); +cursorVLineGeometry.setDrawRange(0, 2); +var cursorVLine = new THREE.Line(cursorVLineGeometry, lightBlueLineMaterial); +cursorVLine.frustumCulled = false; +scene.add(cursorVLine); + +var cursorHLineGeometry = new THREE.BufferGeometry(); +var cursorHLinePositions = new Float32Array(2*3); +cursorHLineGeometry.addAttribute( 'position', new THREE.BufferAttribute(cursorHLinePositions, 3)); +cursorHLineGeometry.setDrawRange(0, 2); +var cursorHLine = new THREE.Line(cursorHLineGeometry, lightBlueLineMaterial); +cursorHLine.frustumCulled = false; +scene.add(cursorHLine); + +var boardCutLinesGeometry = new THREE.BufferGeometry(); +var boardCutLinesPositions = new Float32Array(1000*3); +boardCutLinesGeometry.addAttribute( 'position', new THREE.BufferAttribute(boardCutLinesPositions, 3)); +boardCutLinesGeometry.setDrawRange(0, 100); +var boardCutLines = new THREE.Line(boardCutLinesGeometry, redLineMaterial); +boardCutLines.frustumCulled = false; +scene.add(boardCutLines); + +var boardGroup = new THREE.Group(); + +var boardOutlineGeometry = new THREE.BoxBufferGeometry(96,48,0.75); +var boardFillMaterial = new THREE.MeshBasicMaterial({ color: 0xD2B48C, opacity: 0.5, transparent:true}) +var boardOutlineFill = new THREE.Mesh(boardOutlineGeometry, boardFillMaterial); +var boardOutlineMaterial = new THREE.LineBasicMaterial({ color: 0x783E04}) +var boardEdgesGeometry = new THREE.EdgesGeometry( boardOutlineGeometry ) +var boardOutlineOutline = new THREE.LineSegments( boardEdgesGeometry, boardOutlineMaterial); +boardGroup.add(boardOutlineFill); +boardGroup.add(boardOutlineOutline); + +boardGroup.position.set(0,0,-0.75/2); + +if (showBoard) +{ + scene.add(cutSquareGroup); + scene.add(boardGroup); +} +scene.add(sled); +scene.add(home); +scene.add(gcodePos); +if (!isMobile) + scene.add(cursor); +//scene.add(cutSquareGroup); + +var isComputedEnabled = false; + +animate(); + +window.addEventListener( 'resize', onWindowResize, false ); + +function onWindowResize(){ + + //w=window.innerWidth; + //h=window.innerHeight; + //console.log("wr="+w+", hr="+h); + we = $("#workarea").width(); //-20; + he = $("#workarea").height(); //-20; + //console.log("we="+we+", he="+he); + + //cameraO.aspect = window.innerWidth / window.innerHeight; + cameraO.left = we/-2*scale; + cameraO.right = we/2*scale; + cameraO.top = he/2*scale; + cameraO.bottom = he/-2*scale; + cameraO.updateProjectionMatrix(); + //cameraP.aspect = window.innerWidth / window.innerHeight; + cameraP.aspect = we / he; + cameraP.updateProjectionMatrix(); + + renderer.setSize( we, he ); + +} + + +function animate() { + requestAnimationFrame(animate); + controlsO.update(); + controlsP.update(); + if (cameraPerspective == 0) + renderer.render( scene, cameraO ); + else + renderer.render( scene, cameraP ); +} + +function positionUpdate(x,y,z){ + if ($("#units").text()=="MM"){ + x /= 25.4 + y /= 25.4 + z /= 25.4 + } + sled.position.set(x,y,z); + computedSled.position.setComponent(2,z-0.01); + + //console.log("x="+x+", y="+y+", z="+z) +} + + +function homePositionUpdate(x,y){ + if ($("#units").text()=="MM"){ + x /= 25.4 + y /= 25.4 + } + home.position.set(x,y,0); + //shift any gcode + homeX = x; + homeY = y; + gcode.position.set(x,y,0); + + +} + +function gcodePositionUpdate(x,y,z){ + if ($("#units").text()=="MM"){ + x /= 25.4 + y /= 25.4 + z /= 25.4 + } + gcodePos.position.set(x+homeX,y+homeY,z); + //console.log("x="+x+", y="+y) +} + +$(document).ready(function(){ + $( "#workarea" ).contextmenu(function() { + if (!view3D) + { + pos = cursorPosition(); + + x = pos.x; + x = x.toFixed(4); + pos.x = x; + + y = pos.y; + y = y.toFixed(4); + pos.y = y; + requestPage("screenAction",pos) + } + }); +}); + +function processError3d(data){ + if ( !data.computedEnabled ) + { + if (isComputedEnabled){ + scene.remove(computedSled); + isComputedEnabled = false; + } + return; + } + else + { + var x = data.computedX/25.4; + var y = data.computedY/25.4; + if ($("#units").text()==""){ + x /= 25.4 + y /= 25.4 + } + computedSled.position.setComponent(0,x); + computedSled.position.setComponent(1,y); + if (!isComputedEnabled){ + scene.add(computedSled); + //scene.add(cutTrailGroup); + isComputedEnabled = true; + } + } +} + + +function gcodeUpdateCompressed(data){ + console.log("updating gcode compressed"); + if (gcode.children.length!=0) { + for (var i = gcode.children.length -1; i>=0; i--){ + gcode.remove(gcode.children[i]); + } + } + if (textLabels.children.length!=0) { + for (var i = textLabels.children.length -1; i>=0; i--){ + textLabels.remove(textLabels.children[i]); + } + } + + var gcodeLineSegments = new THREE.Geometry(); + var gcodeDashedLineSegments = new THREE.Geometry(); + + if ((data!=null) && (data!="")){ + var uncompressed = pako.inflate(data); + var _str = ab2str(uncompressed); + var data = JSON.parse(_str) + console.log(data) + var pX, pY, pZ = -99999.9 + var gcodeDashed; + var gcodeUndashed; + data.forEach(function(line) { + if (line.type=='line'){ + //console.log("Line length="+line.points.length+", dashed="+line.dashed); + if (line.dashed==true) { + var gcodeDashedLineSegments = new THREE.Geometry(); + line.points.forEach(function(point) { + gcodeDashedLineSegments.vertices.push(new THREE.Vector3(point[0], point[1], point[2])); + }) + gcodeDashed = new THREE.Line(gcodeDashedLineSegments, greenLineDashedMaterial) + gcodeDashed.computeLineDistances(); + gcode.add(gcodeDashed); + } else { + var gcodeLineSegments = new THREE.Geometry(); + line.points.forEach(function(point) { + gcodeLineSegments.vertices.push(new THREE.Vector3(point[0], point[1], point[2])); + }) + gcodeUndashed = new THREE.Line(gcodeLineSegments, blueLineMaterial) + gcode.add(gcodeUndashed); + + } + } + else + { + if ( (line.command == "SpindleOnCW") || (line.command=="SpindlenOnCCW") || (line.command=="SpindleOff") ) //(line.points[1][0]>=3) && (line.points[1][0]<=5) ) + { + //spindle + var gcodeCircleGeometry = new THREE.CircleGeometry(2.25/32,16); + var gcodeCircleEdges = new THREE.EdgesGeometry(gcodeCircleGeometry) + var circleMaterial = redLineMaterial; + var gcodeCircle = new THREE.LineSegments(gcodeCircleEdges,circleMaterial); + gcodeCircle.position.set(line.points[0][0], line.points[0][1], line.points[0][2]); + gcode.add(gcodeCircle); + var gcodeLineSegments = new THREE.Geometry(); + var xFactor = 3.25; + var yFactor = 3.25; + if (line.command == "SpindleOff") //(line.points[1][0]==5) + { + xFactor = .707107*2.25; + yFactor = .707107*2.25; + } + if (line.command == "SpindleOnCCW") // (line.points[1][0]==4) + { + xFactor = 3.25; + yFactor = 3.25; + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0], line.points[0][1], line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0]+xFactor/32, line.points[0][1]+yFactor/32, line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0]-xFactor/32, line.points[0][1]+yFactor/32, line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0]+xFactor/32, line.points[0][1]-yFactor/32, line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0]-xFactor/32, line.points[0][1]-yFactor/32, line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0], line.points[0][1], line.points[0][2])); + } + else + { + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0], line.points[0][1], line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0]+xFactor/32, line.points[0][1]+yFactor/32, line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0]+xFactor/32, line.points[0][1]-yFactor/32, line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0]-xFactor/32, line.points[0][1]+yFactor/32, line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0]-xFactor/32, line.points[0][1]-yFactor/32, line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0], line.points[0][1], line.points[0][2])); + } + gcodeUndashed = new THREE.Line(gcodeLineSegments, redLineMaterial) + gcode.add(gcodeUndashed); + if (line.command != "SpindleOff") + { + text = new SpriteText('S'+line.points[1][1].toString(),.1, 'red'); + text.position.x = line.points[0][0]; + text.position.y = line.points[0][1]; + text.position.z = line.points[0][2]; + textLabels.add(text); + } + } + else if (line.command == "ToolChange") + { + var gcodeCircleGeometry = new THREE.CircleGeometry(2.25/32,16); + var gcodeCircleEdges = new THREE.EdgesGeometry(gcodeCircleGeometry) + circleMaterial = redLineMaterial; + text = new SpriteText('T'+line.points[1][1].toString(),.1, 'red'); + text.position.x = line.points[0][0]; + text.position.y = line.points[0][1]; + text.position.z = line.points[0][2]; + textLabels.add(text); + var gcodeCircle = new THREE.LineSegments(gcodeCircleEdges,circleMaterial); + gcodeCircle.position.set(line.points[0][0], line.points[0][1], line.points[0][2]); + gcode.add(gcodeCircle); + } + else + { + var gcodeCircleGeometry = new THREE.CircleGeometry(line.points[1][0]/32,16); + var gcodeCircleEdges = new THREE.EdgesGeometry(gcodeCircleGeometry) + var circleMaterial = greenLineMaterial; + var gcodeCircle = new THREE.LineSegments(gcodeCircleEdges,circleMaterial); + gcodeCircle.position.set(line.points[0][0], line.points[0][1], line.points[0][2]); + gcode.add(gcodeCircle); + } + + var gcodeLineSegments = new THREE.Geometry(); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0], line.points[0][1], line.points[0][2])); + gcodeLineSegments.vertices.push(new THREE.Vector3(line.points[0][0], line.points[0][1], line.points[1][2])); + gcodeUndashed = new THREE.Line(gcodeLineSegments, blueLineMaterial) + gcode.add(gcodeUndashed); + + } + }); + scene.add(gcode); + if (showLabels) + scene.add(textLabels); + } + else{ + scene.remove(gcode); + scene.remove(textLabels); + } + $("#fpCircle").hide(); + +} + +function toggleLabels() +{ + if (showLabels) + { + scene.remove(textLabels); + $("#labelsID").removeClass('btn-primary').addClass('btn-secondary'); + } + else + { + scene.add(textLabels); + $("#labelsID").removeClass('btn-secondary').addClass('btn-primary'); + } + showLabels = !showLabels; +} + +function ab2str(buf) { + var bufView = new Uint16Array(buf); + var unis ="" + for (var i = 0; i < bufView.length; i++) { + unis=unis+String.fromCharCode(bufView[i]); + } + return unis +} + +function showFPSpinner(msg){ + $("#fpCircle").show(); +} + + +function toggle3DView() +{ + console.log("toggling"); + if (view3D){ + controlsO.enableRotate = false; + controlsO.mouseButtons = { + LEFT: THREE.MOUSE.RIGHT, + MIDDLE: THREE.MOUSE.MIDDLE, + RIGHT: THREE.MOUSE.LEFT + } + controlsP.enableRotate = false; + controlsP.mouseButtons = { + LEFT: THREE.MOUSE.RIGHT, + MIDDLE: THREE.MOUSE.MIDDLE, + RIGHT: THREE.MOUSE.LEFT + } + + view3D=false; + if (isMobile) + { + $("#mobilebutton3D").removeClass('btn-primary').addClass('btn-secondary'); + } + else + { + $("#button3D").removeClass('btn-primary').addClass('btn-secondary'); + } + console.log("toggled off"); + } else { + controlsO.enableRotate = true; + controlsO.mouseButtons = { + LEFT: THREE.MOUSE.RIGHT, + MIDDLE: THREE.MOUSE.MIDDLE, + RIGHT: THREE.MOUSE.LEFT + } + controlsP.enableRotate = true; + controlsP.mouseButtons = { + LEFT: THREE.MOUSE.RIGHT, + MIDDLE: THREE.MOUSE.MIDDLE, + RIGHT: THREE.MOUSE.LEFT + } + + view3D=true; + if (isMobile) + { + $("#mobilebutton3D").removeClass('btn-secondary').addClass('btn-primary'); + } + else + { + $("#button3D").removeClass('btn-secondary').addClass('btn-primary'); + } + console.log("toggled on"); + } + controlsO.update(); + controlsP.update(); +} + +function resetView(){ + controlsO.reset(); + controlsP.reset(); +} + +function cursorPosition(){ + var rect = renderer.domElement.getBoundingClientRect(); + var vec = new THREE.Vector3(); // create once and reuse + var pos = new THREE.Vector3(); // create once and reuse + vec.set( + ( ( event.clientX - rect.left ) / ( rect.right - rect.left ) ) * 2 - 1, + - ( ( event.clientY - rect.top ) / ( rect.bottom - rect.top) ) * 2 + 1, + 0.5 ); + + if (cameraPerspective == 0) + { + vec.unproject( cameraO ); + vec.sub( cameraO.position ).normalize(); + var distance = - cameraO.position.z / vec.z; + pos.copy( cameraO.position ).add( vec.multiplyScalar( distance ) ); + } + else + { + vec.unproject( cameraP ); + vec.sub( cameraP.position ).normalize(); + var distance = - cameraP.position.z / vec.z; + pos.copy( cameraP.position ).add( vec.multiplyScalar( distance ) ); + } + //console.log(pos); + return(pos); +} + +function processCameraMessage(data){ + if(data.command=="cameraImageUpdated"){ + var newImg = new Image(); + if (imageShowing==1) + { + newImg.onload = function() { + document.getElementById("cameraImage2").setAttribute('src',this.src); + if (isMobile){ + document.getElementById("mobileCameraDiv2").style.zIndex = "95"; + document.getElementById("mobileCameraDiv1").style.zIndex = "94"; + } else { + document.getElementById("cameraDiv2").style.zIndex = "95"; + document.getElementById("cameraDiv1").style.zIndex = "94"; + } + imageShowing = 2 + } + } + else + { + newImg.onload = function() { + document.getElementById("cameraImage1").setAttribute('src',this.src); + if (isMobile){ + document.getElementById("mobileCameraDiv1").style.zIndex = "95"; + document.getElementById("mobileCameraDiv2").style.zIndex = "94"; + } else { + document.getElementById("cameraDiv1").style.zIndex = "95"; + document.getElementById("cameraDiv2").style.zIndex = "94"; + } + imageShowing = 1 + } + } + newImg.setAttribute('src', 'data:image/png;base64,'+data.data) + + } + if(data.command=="updateCamera") + { + if (data.data=="on"){ + $("#videoStatus svg.feather.feather-video-off").replaceWith(feather.icons.video.toSvg()); + feather.replace(); + console.log("video on"); + document.getElementById("cameraImage1").style.display = "block" + document.getElementById("cameraImage2").style.display = "block" + if (isMobile) + document.getElementById("mobileCameraArea").style.display = "block" + } + + if (data.data=="off"){ + $("#videoStatus svg.feather.feather-video").replaceWith(feather.icons["video-off"].toSvg()); + feather.replace(); + console.log("video off") + document.getElementById("cameraImage1").style.display = "none"; + document.getElementById("cameraImage2").style.display = "none" + if (isMobile) + document.getElementById("mobileCameraArea").style.display = "none" + } + } +} + +document.onmousemove = function(event){ + if (!isMobile) + { + pos = cursorPosition(); + cursor.position.set(pos.x,pos.y,pos.z); + var linePosX = confine(pos.x,-48, 48); + var linePosY = confine(pos.y,-24, 24); + + var positions = cursorVLine.geometry.attributes.position.array; + positions[0]=linePosX; + positions[1]=24; + positions[2]=-0.001; + positions[3]=linePosX; + positions[4]=-24; + positions[5]=-0.001; + cursorVLine.geometry.attributes.position.needsUpdate=true; + + positions = cursorHLine.geometry.attributes.position.array; + positions[0]=48; + positions[1]=linePosY; + positions[2]=-0.001; + positions[3]=-48; + positions[4]=linePosY; + positions[5]=-0.001; + cursorHLine.geometry.attributes.position.needsUpdate=true; + + + if ($("#units").text()=="MM"){ + pos.x *= 25.4 + pos.y *= 25.4 + } + $("#cursorPosition").text("X: "+pos.x.toFixed(2)+", Y: "+pos.y.toFixed(2)); + } +} + +function confine(value, low, high) +{ + if (valuehigh) + return high; + return value; +} + +function board3DDataUpdate(data){ + console.log("updating board data"); + boardOutlineGeometry.dispose(); + boardOutlineGeometry = new THREE.BoxBufferGeometry(boardWidth,boardHeight,boardThickness); + boardOutlineFill.geometry = boardOutlineGeometry; + boardEdgesGeometry = new THREE.EdgesGeometry( boardOutlineGeometry ) + boardOutlineOutline.geometry = boardEdgesGeometry; + + boardOutlineFill.geometry.needsUpdate=true; + boardOutlineOutline.geometry.needsUpdate=true; + boardGroup.position.set(boardCenterX,boardCenterY,boardThickness/-2.0); + +} + +function boardCutDataUpdateCompressed(data){ + console.log("updating board cut data compressed"); + if (cutSquareGroup.children.length!=0) { + for (var i = cutSquareGroup.children.length -1; i>=0; i--){ + cutSquareGroup.remove(cutSquareGroup.children[i]); + } + } + if (data!=null){ + //var cutSquareMaterial = new THREE.MeshBasicMaterial( {color:0xffff00, side: THREE.DoubleSide}); + var cutSquareMaterial = new THREE.MeshBasicMaterial( {color:0xff6666}); + var noncutSquareMaterial = new THREE.MeshBasicMaterial( {color:0x333333}); + var uncompressed = pako.inflate(data); + var _str = ab2str(uncompressed); + var data = JSON.parse(_str) + + var pointsX = Math.ceil(boardWidth) + var pointsY = Math.ceil(boardHeight) + console.log("boardWidth="+boardWidth) + console.log("boardHeight="+boardHeight) + console.log("boardCenterY="+boardCenterY) + var offsetX = pointsX / 2 + var offsetY = pointsY / 2 + + for (var x =0; x100) + controllerMessages.shift(); + controllerMessages.push(data); + $('#controllerMessage').html(''); + controllerMessages.forEach(function(message){ + $('#controllerMessage').append(message+"
"); + }); + $('#controllerMessage').scrollBottom(); +} + +function processAlarm(data){ + console.log("alarm received"); + $("#alarms").html(""+data.message+""); + $("#alarms").removeClass('alert-success').addClass('alert-danger'); + $("#stopButton").addClass('stopbutton'); +} + +function clearAlarm(data){ + console.log("clearing alarm"); + $("#alarms").text("Alarm cleared."); + $("#alarms").removeClass('alert-danger').addClass('alert-success'); +} + +function processStatusMessage(data){ + if (data.uploadFlag == 1){ + if (!isDisabled){ + $('.disabler').prop('disabled', true); + isDisabled = true; + } + } else { + if (isDisabled){ + $('.disabler').prop('disabled', false); + isDisabled = false; + } + } + $("#currentTool").text(data.currentTool.toString()); + if (data.positioningMode == 0) + $("#currentPositioningMode").text("Absolute (G90)"); + else + $("#currentPositioningMode").text("Incremental (G91)"); +} diff --git a/static/scripts/frontpageControls.js b/static/scripts/frontpageControls.js new file mode 100644 index 00000000..dc0bb784 --- /dev/null +++ b/static/scripts/frontpageControls.js @@ -0,0 +1,168 @@ + +var boardWidth = 96 +var boardHeight = 48 +var boardThickness = 0.75 +var boardCenterX = 0 +var boardCenterY = 0 +var boardID = "-" +var boardMaterial = "-" + +function unitSwitch(){ + if ( $("#units").text()=="MM") { + distToMove = (parseFloat($("#distToMove").val())/25.4).toFixed(3) + updateSetting('toInches',distToMove); + } else { + distToMove = (parseFloat($("#distToMove").val())*25.4).toFixed(3) + updateSetting('toMM',distToMove); + } +} + +$(document).ready(function(){ + action("statusRequest","cameraStatus"); + var controllerMessage = document.getElementById('controllerMessage'); + controllerMessage.scrollTop = controllerMessage.scrollHeight; + $("#stickyButtons").css("top", $(".navbar").outerHeight()); +}); + +function pauseRun(){ + if ($("#pauseButton").text()=="Pause"){ + action('pauseRun'); + } + else { + action('resumeRun'); + } +} + +function resumeRun(){ + action('resumeRun') +} + +function processRequestedSetting(data){ + //console.log(data); + if (data.setting=="pauseButtonSetting"){ + if(data.value=="Resume") + $('#pauseButton').removeClass('btn-warning').addClass('btn-info'); + else + $('#pauseButton').removeClass('btn-info').addClass('btn-warning'); + $("#pauseButton").text(data.value); + } + if (data.setting=="units"){ + console.log("requestedSetting:"+data.value); + $("#units").text(data.value) + } + if (data.setting=="distToMove"){ + console.log("requestedSetting for distToMove:"+data.value); + $("#distToMove").val(data.value) + } + if ((data.setting=="unitsZ") || (data.setting=="distToMoveZ")){ + if (typeof processZAxisRequestedSetting === "function") { + processZAxisRequestedSetting(data) + } + } +} + +function processPositionMessage(data){ + $('#positionMessage').html('X:'+parseFloat(data.xval).toFixed(2)+' Y:'+parseFloat(data.yval).toFixed(2)+' Z:'+parseFloat(data.zval).toFixed(2)); + $('#percentComplete').html(data.pcom) + $('#machineState').html(data.state) + if (enable3D) + positionUpdate(data.xval,data.yval,data.zval); +} + +function processErrorValueMessage(data){ + $('#leftError').css('width', data.leftError*100+'%').attr('aria-valuenow', data.leftError*100); + $('#rightError').css('width', data.rightError*100+'%').attr('aria-valuenow', data.rightError*100); + if (enable3D){ + processError3d(data) + } +} + + +function processHomePositionMessage(data){ + console.log(data.xval) + $('#homePositionMessage').html('X:'+parseFloat(data.xval).toFixed(2)+' Y:'+parseFloat(data.yval).toFixed(2)); + if (enable3D) + homePositionUpdate(data.xval,data.yval); +} + +function processGCodePositionMessage(data){ + $('#gcodePositionMessage').html('X:'+parseFloat(data.xval).toFixed(2)+' Y:'+parseFloat(data.yval).toFixed(2)+' Z:'+parseFloat(data.zval).toFixed(2)); + $('#gcodeLine').html(data.gcodeLine); + $('#gcodeLineIndex').val(data.gcodeLineIndex+1) + if (enable3D) + gcodePositionUpdate(data.xval,data.yval,data.zval); +} + +function showFPSpinner(msg){ + $("#fpCircle").show(); +} + +function processControllerMessage(data){ + if (controllerMessages.length >100) + controllerMessages.shift(); + controllerMessages.push(data); + $('#controllerMessage').html(''); + controllerMessages.forEach(function(message){ + $('#controllerMessage').append(message+"
"); + }); + $('#controllerMessage').scrollBottom(); +} + +function processAlarm(data){ + console.log("alarm received"); + $("#alarms").html(""+data.message+""); + $("#alarms").removeClass('alert-success').addClass('alert-danger'); + $("#stopButton").addClass('stopbutton'); +} + +function clearAlarm(data){ + console.log("clearing alarm"); + $("#alarms").text("Alarm cleared."); + $("#alarms").removeClass('alert-danger').addClass('alert-success'); + $("#stopButton").removeClass('stopbutton'); +} + + +function boardDataUpdate(data){ + console.log("updating board data"); + boardWidth = data.width; + boardHeight = data.height; + boardThickness = data.thickness; + boardCenterX = data.centerX; + boardCenterY = data.centerY; + boardID = data.boardID; + boardMaterial = data.material; + $("#boardID").text("Board: "+boardID+", Material: "+boardMaterial); + if (enable3D) + board3DDataUpdate(data); +} + +function moveAction(direction) { + distance = $("#distToMove").val(); + distanceValid = distance.search(/^[0-9]*(\.[0-9]{0,3})?$/); + if (distanceValid == 0) { + action('move', direction, distance); + } else { + $("#distToMove").focus(); + } +} + +function processStatusMessage(data){ + //console.log(data) + if (data.uploadFlag){ + if (!isDisabled){ + $('.disabler').prop('disabled', true); + isDisabled = true; + } + } else { + if (isDisabled){ + $('.disabler').prop('disabled', false); + isDisabled = false; + } + } + $("#currentTool").text(data.currentTool.toString()); + if (data.positioningMode == 0) + $("#currentPositioningMode").text("Absolute (G90)"); + else + $("#currentPositioningMode").text("Incremental (G91)"); +} diff --git a/static/scripts/gcode_hightlight_rules.js b/static/scripts/gcode_hightlight_rules.js new file mode 100644 index 00000000..9913dbee --- /dev/null +++ b/static/scripts/gcode_hightlight_rules.js @@ -0,0 +1,26 @@ +define(function(require, exports, module) { +"use strict"; + +var oop = require("../lib/oop"); +var TextHighlightRules = require("./text_highlight_rules").TextHighlightRules; + +var MyNewHighlightRules = function() { + + // regexp must not have capturing parentheses. Use (?:) instead. + // regexps are ordered -> the first match is used + this.$rules = { + "start" : [ + { + token: token, // String, Array, or Function: the CSS token to apply + regex: regex, // String or RegExp: the regexp to match + next: next // [Optional] String: next state to enter + } + ] + }; +}; + +oop.inherits(MyNewHighlightRules, TextHighlightRules); + +exports.MyNewHighlightRules = MyNewHighlightRules; + +}); \ No newline at end of file diff --git a/static/scripts/holeyCalibration.js b/static/scripts/holeyCalibration.js new file mode 100644 index 00000000..e69de29b diff --git a/static/scripts/jquery-3.3.1.min.js b/static/scripts/jquery-3.3.1.min.js new file mode 100644 index 00000000..49d1fcfb --- /dev/null +++ b/static/scripts/jquery-3.3.1.min.js @@ -0,0 +1,2 @@ +/*! jQuery v3.3.1 | (c) JS Foundation and other contributors | jquery.org/license */ +!function(e,t){"use strict";"object"==typeof module&&"object"==typeof module.exports?module.exports=e.document?t(e,!0):function(e){if(!e.document)throw new Error("jQuery requires a window with a document");return t(e)}:t(e)}("undefined"!=typeof window?window:this,function(e,t){"use strict";var n=[],r=e.document,i=Object.getPrototypeOf,o=n.slice,a=n.concat,s=n.push,u=n.indexOf,l={},c=l.toString,f=l.hasOwnProperty,p=f.toString,d=p.call(Object),h={},g=function e(t){return"function"==typeof t&&"number"!=typeof t.nodeType},y=function e(t){return null!=t&&t===t.window},v={type:!0,src:!0,noModule:!0};function m(e,t,n){var i,o=(t=t||r).createElement("script");if(o.text=e,n)for(i in v)n[i]&&(o[i]=n[i]);t.head.appendChild(o).parentNode.removeChild(o)}function x(e){return null==e?e+"":"object"==typeof e||"function"==typeof e?l[c.call(e)]||"object":typeof e}var b="3.3.1",w=function(e,t){return new w.fn.init(e,t)},T=/^[\s\uFEFF\xA0]+|[\s\uFEFF\xA0]+$/g;w.fn=w.prototype={jquery:"3.3.1",constructor:w,length:0,toArray:function(){return o.call(this)},get:function(e){return null==e?o.call(this):e<0?this[e+this.length]:this[e]},pushStack:function(e){var t=w.merge(this.constructor(),e);return t.prevObject=this,t},each:function(e){return w.each(this,e)},map:function(e){return this.pushStack(w.map(this,function(t,n){return e.call(t,n,t)}))},slice:function(){return this.pushStack(o.apply(this,arguments))},first:function(){return this.eq(0)},last:function(){return this.eq(-1)},eq:function(e){var t=this.length,n=+e+(e<0?t:0);return this.pushStack(n>=0&&n0&&t-1 in e)}var E=function(e){var t,n,r,i,o,a,s,u,l,c,f,p,d,h,g,y,v,m,x,b="sizzle"+1*new Date,w=e.document,T=0,C=0,E=ae(),k=ae(),S=ae(),D=function(e,t){return e===t&&(f=!0),0},N={}.hasOwnProperty,A=[],j=A.pop,q=A.push,L=A.push,H=A.slice,O=function(e,t){for(var n=0,r=e.length;n+~]|"+M+")"+M+"*"),z=new RegExp("="+M+"*([^\\]'\"]*?)"+M+"*\\]","g"),X=new RegExp(W),U=new RegExp("^"+R+"$"),V={ID:new RegExp("^#("+R+")"),CLASS:new RegExp("^\\.("+R+")"),TAG:new RegExp("^("+R+"|[*])"),ATTR:new RegExp("^"+I),PSEUDO:new RegExp("^"+W),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+M+"*(even|odd|(([+-]|)(\\d*)n|)"+M+"*(?:([+-]|)"+M+"*(\\d+)|))"+M+"*\\)|)","i"),bool:new RegExp("^(?:"+P+")$","i"),needsContext:new RegExp("^"+M+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+M+"*((?:-\\d)?\\d*)"+M+"*\\)|)(?=[^-]|$)","i")},G=/^(?:input|select|textarea|button)$/i,Y=/^h\d$/i,Q=/^[^{]+\{\s*\[native \w/,J=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,K=/[+~]/,Z=new RegExp("\\\\([\\da-f]{1,6}"+M+"?|("+M+")|.)","ig"),ee=function(e,t,n){var r="0x"+t-65536;return r!==r||n?t:r<0?String.fromCharCode(r+65536):String.fromCharCode(r>>10|55296,1023&r|56320)},te=/([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g,ne=function(e,t){return t?"\0"===e?"\ufffd":e.slice(0,-1)+"\\"+e.charCodeAt(e.length-1).toString(16)+" ":"\\"+e},re=function(){p()},ie=me(function(e){return!0===e.disabled&&("form"in e||"label"in e)},{dir:"parentNode",next:"legend"});try{L.apply(A=H.call(w.childNodes),w.childNodes),A[w.childNodes.length].nodeType}catch(e){L={apply:A.length?function(e,t){q.apply(e,H.call(t))}:function(e,t){var n=e.length,r=0;while(e[n++]=t[r++]);e.length=n-1}}}function oe(e,t,r,i){var o,s,l,c,f,h,v,m=t&&t.ownerDocument,T=t?t.nodeType:9;if(r=r||[],"string"!=typeof e||!e||1!==T&&9!==T&&11!==T)return r;if(!i&&((t?t.ownerDocument||t:w)!==d&&p(t),t=t||d,g)){if(11!==T&&(f=J.exec(e)))if(o=f[1]){if(9===T){if(!(l=t.getElementById(o)))return r;if(l.id===o)return r.push(l),r}else if(m&&(l=m.getElementById(o))&&x(t,l)&&l.id===o)return r.push(l),r}else{if(f[2])return L.apply(r,t.getElementsByTagName(e)),r;if((o=f[3])&&n.getElementsByClassName&&t.getElementsByClassName)return L.apply(r,t.getElementsByClassName(o)),r}if(n.qsa&&!S[e+" "]&&(!y||!y.test(e))){if(1!==T)m=t,v=e;else if("object"!==t.nodeName.toLowerCase()){(c=t.getAttribute("id"))?c=c.replace(te,ne):t.setAttribute("id",c=b),s=(h=a(e)).length;while(s--)h[s]="#"+c+" "+ve(h[s]);v=h.join(","),m=K.test(e)&&ge(t.parentNode)||t}if(v)try{return L.apply(r,m.querySelectorAll(v)),r}catch(e){}finally{c===b&&t.removeAttribute("id")}}}return u(e.replace(B,"$1"),t,r,i)}function ae(){var e=[];function t(n,i){return e.push(n+" ")>r.cacheLength&&delete t[e.shift()],t[n+" "]=i}return t}function se(e){return e[b]=!0,e}function ue(e){var t=d.createElement("fieldset");try{return!!e(t)}catch(e){return!1}finally{t.parentNode&&t.parentNode.removeChild(t),t=null}}function le(e,t){var n=e.split("|"),i=n.length;while(i--)r.attrHandle[n[i]]=t}function ce(e,t){var n=t&&e,r=n&&1===e.nodeType&&1===t.nodeType&&e.sourceIndex-t.sourceIndex;if(r)return r;if(n)while(n=n.nextSibling)if(n===t)return-1;return e?1:-1}function fe(e){return function(t){return"input"===t.nodeName.toLowerCase()&&t.type===e}}function pe(e){return function(t){var n=t.nodeName.toLowerCase();return("input"===n||"button"===n)&&t.type===e}}function de(e){return function(t){return"form"in t?t.parentNode&&!1===t.disabled?"label"in t?"label"in t.parentNode?t.parentNode.disabled===e:t.disabled===e:t.isDisabled===e||t.isDisabled!==!e&&ie(t)===e:t.disabled===e:"label"in t&&t.disabled===e}}function he(e){return se(function(t){return t=+t,se(function(n,r){var i,o=e([],n.length,t),a=o.length;while(a--)n[i=o[a]]&&(n[i]=!(r[i]=n[i]))})})}function ge(e){return e&&"undefined"!=typeof e.getElementsByTagName&&e}n=oe.support={},o=oe.isXML=function(e){var t=e&&(e.ownerDocument||e).documentElement;return!!t&&"HTML"!==t.nodeName},p=oe.setDocument=function(e){var t,i,a=e?e.ownerDocument||e:w;return a!==d&&9===a.nodeType&&a.documentElement?(d=a,h=d.documentElement,g=!o(d),w!==d&&(i=d.defaultView)&&i.top!==i&&(i.addEventListener?i.addEventListener("unload",re,!1):i.attachEvent&&i.attachEvent("onunload",re)),n.attributes=ue(function(e){return e.className="i",!e.getAttribute("className")}),n.getElementsByTagName=ue(function(e){return e.appendChild(d.createComment("")),!e.getElementsByTagName("*").length}),n.getElementsByClassName=Q.test(d.getElementsByClassName),n.getById=ue(function(e){return h.appendChild(e).id=b,!d.getElementsByName||!d.getElementsByName(b).length}),n.getById?(r.filter.ID=function(e){var t=e.replace(Z,ee);return function(e){return e.getAttribute("id")===t}},r.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&g){var n=t.getElementById(e);return n?[n]:[]}}):(r.filter.ID=function(e){var t=e.replace(Z,ee);return function(e){var n="undefined"!=typeof e.getAttributeNode&&e.getAttributeNode("id");return n&&n.value===t}},r.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&g){var n,r,i,o=t.getElementById(e);if(o){if((n=o.getAttributeNode("id"))&&n.value===e)return[o];i=t.getElementsByName(e),r=0;while(o=i[r++])if((n=o.getAttributeNode("id"))&&n.value===e)return[o]}return[]}}),r.find.TAG=n.getElementsByTagName?function(e,t){return"undefined"!=typeof t.getElementsByTagName?t.getElementsByTagName(e):n.qsa?t.querySelectorAll(e):void 0}:function(e,t){var n,r=[],i=0,o=t.getElementsByTagName(e);if("*"===e){while(n=o[i++])1===n.nodeType&&r.push(n);return r}return o},r.find.CLASS=n.getElementsByClassName&&function(e,t){if("undefined"!=typeof t.getElementsByClassName&&g)return t.getElementsByClassName(e)},v=[],y=[],(n.qsa=Q.test(d.querySelectorAll))&&(ue(function(e){h.appendChild(e).innerHTML="",e.querySelectorAll("[msallowcapture^='']").length&&y.push("[*^$]="+M+"*(?:''|\"\")"),e.querySelectorAll("[selected]").length||y.push("\\["+M+"*(?:value|"+P+")"),e.querySelectorAll("[id~="+b+"-]").length||y.push("~="),e.querySelectorAll(":checked").length||y.push(":checked"),e.querySelectorAll("a#"+b+"+*").length||y.push(".#.+[+~]")}),ue(function(e){e.innerHTML="";var t=d.createElement("input");t.setAttribute("type","hidden"),e.appendChild(t).setAttribute("name","D"),e.querySelectorAll("[name=d]").length&&y.push("name"+M+"*[*^$|!~]?="),2!==e.querySelectorAll(":enabled").length&&y.push(":enabled",":disabled"),h.appendChild(e).disabled=!0,2!==e.querySelectorAll(":disabled").length&&y.push(":enabled",":disabled"),e.querySelectorAll("*,:x"),y.push(",.*:")})),(n.matchesSelector=Q.test(m=h.matches||h.webkitMatchesSelector||h.mozMatchesSelector||h.oMatchesSelector||h.msMatchesSelector))&&ue(function(e){n.disconnectedMatch=m.call(e,"*"),m.call(e,"[s!='']:x"),v.push("!=",W)}),y=y.length&&new RegExp(y.join("|")),v=v.length&&new RegExp(v.join("|")),t=Q.test(h.compareDocumentPosition),x=t||Q.test(h.contains)?function(e,t){var n=9===e.nodeType?e.documentElement:e,r=t&&t.parentNode;return e===r||!(!r||1!==r.nodeType||!(n.contains?n.contains(r):e.compareDocumentPosition&&16&e.compareDocumentPosition(r)))}:function(e,t){if(t)while(t=t.parentNode)if(t===e)return!0;return!1},D=t?function(e,t){if(e===t)return f=!0,0;var r=!e.compareDocumentPosition-!t.compareDocumentPosition;return r||(1&(r=(e.ownerDocument||e)===(t.ownerDocument||t)?e.compareDocumentPosition(t):1)||!n.sortDetached&&t.compareDocumentPosition(e)===r?e===d||e.ownerDocument===w&&x(w,e)?-1:t===d||t.ownerDocument===w&&x(w,t)?1:c?O(c,e)-O(c,t):0:4&r?-1:1)}:function(e,t){if(e===t)return f=!0,0;var n,r=0,i=e.parentNode,o=t.parentNode,a=[e],s=[t];if(!i||!o)return e===d?-1:t===d?1:i?-1:o?1:c?O(c,e)-O(c,t):0;if(i===o)return ce(e,t);n=e;while(n=n.parentNode)a.unshift(n);n=t;while(n=n.parentNode)s.unshift(n);while(a[r]===s[r])r++;return r?ce(a[r],s[r]):a[r]===w?-1:s[r]===w?1:0},d):d},oe.matches=function(e,t){return oe(e,null,null,t)},oe.matchesSelector=function(e,t){if((e.ownerDocument||e)!==d&&p(e),t=t.replace(z,"='$1']"),n.matchesSelector&&g&&!S[t+" "]&&(!v||!v.test(t))&&(!y||!y.test(t)))try{var r=m.call(e,t);if(r||n.disconnectedMatch||e.document&&11!==e.document.nodeType)return r}catch(e){}return oe(t,d,null,[e]).length>0},oe.contains=function(e,t){return(e.ownerDocument||e)!==d&&p(e),x(e,t)},oe.attr=function(e,t){(e.ownerDocument||e)!==d&&p(e);var i=r.attrHandle[t.toLowerCase()],o=i&&N.call(r.attrHandle,t.toLowerCase())?i(e,t,!g):void 0;return void 0!==o?o:n.attributes||!g?e.getAttribute(t):(o=e.getAttributeNode(t))&&o.specified?o.value:null},oe.escape=function(e){return(e+"").replace(te,ne)},oe.error=function(e){throw new Error("Syntax error, unrecognized expression: "+e)},oe.uniqueSort=function(e){var t,r=[],i=0,o=0;if(f=!n.detectDuplicates,c=!n.sortStable&&e.slice(0),e.sort(D),f){while(t=e[o++])t===e[o]&&(i=r.push(o));while(i--)e.splice(r[i],1)}return c=null,e},i=oe.getText=function(e){var t,n="",r=0,o=e.nodeType;if(o){if(1===o||9===o||11===o){if("string"==typeof e.textContent)return e.textContent;for(e=e.firstChild;e;e=e.nextSibling)n+=i(e)}else if(3===o||4===o)return e.nodeValue}else while(t=e[r++])n+=i(t);return n},(r=oe.selectors={cacheLength:50,createPseudo:se,match:V,attrHandle:{},find:{},relative:{">":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(e){return e[1]=e[1].replace(Z,ee),e[3]=(e[3]||e[4]||e[5]||"").replace(Z,ee),"~="===e[2]&&(e[3]=" "+e[3]+" "),e.slice(0,4)},CHILD:function(e){return e[1]=e[1].toLowerCase(),"nth"===e[1].slice(0,3)?(e[3]||oe.error(e[0]),e[4]=+(e[4]?e[5]+(e[6]||1):2*("even"===e[3]||"odd"===e[3])),e[5]=+(e[7]+e[8]||"odd"===e[3])):e[3]&&oe.error(e[0]),e},PSEUDO:function(e){var t,n=!e[6]&&e[2];return V.CHILD.test(e[0])?null:(e[3]?e[2]=e[4]||e[5]||"":n&&X.test(n)&&(t=a(n,!0))&&(t=n.indexOf(")",n.length-t)-n.length)&&(e[0]=e[0].slice(0,t),e[2]=n.slice(0,t)),e.slice(0,3))}},filter:{TAG:function(e){var t=e.replace(Z,ee).toLowerCase();return"*"===e?function(){return!0}:function(e){return e.nodeName&&e.nodeName.toLowerCase()===t}},CLASS:function(e){var t=E[e+" "];return t||(t=new RegExp("(^|"+M+")"+e+"("+M+"|$)"))&&E(e,function(e){return t.test("string"==typeof e.className&&e.className||"undefined"!=typeof e.getAttribute&&e.getAttribute("class")||"")})},ATTR:function(e,t,n){return function(r){var i=oe.attr(r,e);return null==i?"!="===t:!t||(i+="","="===t?i===n:"!="===t?i!==n:"^="===t?n&&0===i.indexOf(n):"*="===t?n&&i.indexOf(n)>-1:"$="===t?n&&i.slice(-n.length)===n:"~="===t?(" "+i.replace($," ")+" ").indexOf(n)>-1:"|="===t&&(i===n||i.slice(0,n.length+1)===n+"-"))}},CHILD:function(e,t,n,r,i){var o="nth"!==e.slice(0,3),a="last"!==e.slice(-4),s="of-type"===t;return 1===r&&0===i?function(e){return!!e.parentNode}:function(t,n,u){var l,c,f,p,d,h,g=o!==a?"nextSibling":"previousSibling",y=t.parentNode,v=s&&t.nodeName.toLowerCase(),m=!u&&!s,x=!1;if(y){if(o){while(g){p=t;while(p=p[g])if(s?p.nodeName.toLowerCase()===v:1===p.nodeType)return!1;h=g="only"===e&&!h&&"nextSibling"}return!0}if(h=[a?y.firstChild:y.lastChild],a&&m){x=(d=(l=(c=(f=(p=y)[b]||(p[b]={}))[p.uniqueID]||(f[p.uniqueID]={}))[e]||[])[0]===T&&l[1])&&l[2],p=d&&y.childNodes[d];while(p=++d&&p&&p[g]||(x=d=0)||h.pop())if(1===p.nodeType&&++x&&p===t){c[e]=[T,d,x];break}}else if(m&&(x=d=(l=(c=(f=(p=t)[b]||(p[b]={}))[p.uniqueID]||(f[p.uniqueID]={}))[e]||[])[0]===T&&l[1]),!1===x)while(p=++d&&p&&p[g]||(x=d=0)||h.pop())if((s?p.nodeName.toLowerCase()===v:1===p.nodeType)&&++x&&(m&&((c=(f=p[b]||(p[b]={}))[p.uniqueID]||(f[p.uniqueID]={}))[e]=[T,x]),p===t))break;return(x-=i)===r||x%r==0&&x/r>=0}}},PSEUDO:function(e,t){var n,i=r.pseudos[e]||r.setFilters[e.toLowerCase()]||oe.error("unsupported pseudo: "+e);return i[b]?i(t):i.length>1?(n=[e,e,"",t],r.setFilters.hasOwnProperty(e.toLowerCase())?se(function(e,n){var r,o=i(e,t),a=o.length;while(a--)e[r=O(e,o[a])]=!(n[r]=o[a])}):function(e){return i(e,0,n)}):i}},pseudos:{not:se(function(e){var t=[],n=[],r=s(e.replace(B,"$1"));return r[b]?se(function(e,t,n,i){var o,a=r(e,null,i,[]),s=e.length;while(s--)(o=a[s])&&(e[s]=!(t[s]=o))}):function(e,i,o){return t[0]=e,r(t,null,o,n),t[0]=null,!n.pop()}}),has:se(function(e){return function(t){return oe(e,t).length>0}}),contains:se(function(e){return e=e.replace(Z,ee),function(t){return(t.textContent||t.innerText||i(t)).indexOf(e)>-1}}),lang:se(function(e){return U.test(e||"")||oe.error("unsupported lang: "+e),e=e.replace(Z,ee).toLowerCase(),function(t){var n;do{if(n=g?t.lang:t.getAttribute("xml:lang")||t.getAttribute("lang"))return(n=n.toLowerCase())===e||0===n.indexOf(e+"-")}while((t=t.parentNode)&&1===t.nodeType);return!1}}),target:function(t){var n=e.location&&e.location.hash;return n&&n.slice(1)===t.id},root:function(e){return e===h},focus:function(e){return e===d.activeElement&&(!d.hasFocus||d.hasFocus())&&!!(e.type||e.href||~e.tabIndex)},enabled:de(!1),disabled:de(!0),checked:function(e){var t=e.nodeName.toLowerCase();return"input"===t&&!!e.checked||"option"===t&&!!e.selected},selected:function(e){return e.parentNode&&e.parentNode.selectedIndex,!0===e.selected},empty:function(e){for(e=e.firstChild;e;e=e.nextSibling)if(e.nodeType<6)return!1;return!0},parent:function(e){return!r.pseudos.empty(e)},header:function(e){return Y.test(e.nodeName)},input:function(e){return G.test(e.nodeName)},button:function(e){var t=e.nodeName.toLowerCase();return"input"===t&&"button"===e.type||"button"===t},text:function(e){var t;return"input"===e.nodeName.toLowerCase()&&"text"===e.type&&(null==(t=e.getAttribute("type"))||"text"===t.toLowerCase())},first:he(function(){return[0]}),last:he(function(e,t){return[t-1]}),eq:he(function(e,t,n){return[n<0?n+t:n]}),even:he(function(e,t){for(var n=0;n=0;)e.push(r);return e}),gt:he(function(e,t,n){for(var r=n<0?n+t:n;++r1?function(t,n,r){var i=e.length;while(i--)if(!e[i](t,n,r))return!1;return!0}:e[0]}function be(e,t,n){for(var r=0,i=t.length;r-1&&(o[l]=!(a[l]=f))}}else v=we(v===a?v.splice(h,v.length):v),i?i(null,a,v,u):L.apply(a,v)})}function Ce(e){for(var t,n,i,o=e.length,a=r.relative[e[0].type],s=a||r.relative[" "],u=a?1:0,c=me(function(e){return e===t},s,!0),f=me(function(e){return O(t,e)>-1},s,!0),p=[function(e,n,r){var i=!a&&(r||n!==l)||((t=n).nodeType?c(e,n,r):f(e,n,r));return t=null,i}];u1&&xe(p),u>1&&ve(e.slice(0,u-1).concat({value:" "===e[u-2].type?"*":""})).replace(B,"$1"),n,u0,i=e.length>0,o=function(o,a,s,u,c){var f,h,y,v=0,m="0",x=o&&[],b=[],w=l,C=o||i&&r.find.TAG("*",c),E=T+=null==w?1:Math.random()||.1,k=C.length;for(c&&(l=a===d||a||c);m!==k&&null!=(f=C[m]);m++){if(i&&f){h=0,a||f.ownerDocument===d||(p(f),s=!g);while(y=e[h++])if(y(f,a||d,s)){u.push(f);break}c&&(T=E)}n&&((f=!y&&f)&&v--,o&&x.push(f))}if(v+=m,n&&m!==v){h=0;while(y=t[h++])y(x,b,a,s);if(o){if(v>0)while(m--)x[m]||b[m]||(b[m]=j.call(u));b=we(b)}L.apply(u,b),c&&!o&&b.length>0&&v+t.length>1&&oe.uniqueSort(u)}return c&&(T=E,l=w),x};return n?se(o):o}return s=oe.compile=function(e,t){var n,r=[],i=[],o=S[e+" "];if(!o){t||(t=a(e)),n=t.length;while(n--)(o=Ce(t[n]))[b]?r.push(o):i.push(o);(o=S(e,Ee(i,r))).selector=e}return o},u=oe.select=function(e,t,n,i){var o,u,l,c,f,p="function"==typeof e&&e,d=!i&&a(e=p.selector||e);if(n=n||[],1===d.length){if((u=d[0]=d[0].slice(0)).length>2&&"ID"===(l=u[0]).type&&9===t.nodeType&&g&&r.relative[u[1].type]){if(!(t=(r.find.ID(l.matches[0].replace(Z,ee),t)||[])[0]))return n;p&&(t=t.parentNode),e=e.slice(u.shift().value.length)}o=V.needsContext.test(e)?0:u.length;while(o--){if(l=u[o],r.relative[c=l.type])break;if((f=r.find[c])&&(i=f(l.matches[0].replace(Z,ee),K.test(u[0].type)&&ge(t.parentNode)||t))){if(u.splice(o,1),!(e=i.length&&ve(u)))return L.apply(n,i),n;break}}}return(p||s(e,d))(i,t,!g,n,!t||K.test(e)&&ge(t.parentNode)||t),n},n.sortStable=b.split("").sort(D).join("")===b,n.detectDuplicates=!!f,p(),n.sortDetached=ue(function(e){return 1&e.compareDocumentPosition(d.createElement("fieldset"))}),ue(function(e){return e.innerHTML="","#"===e.firstChild.getAttribute("href")})||le("type|href|height|width",function(e,t,n){if(!n)return e.getAttribute(t,"type"===t.toLowerCase()?1:2)}),n.attributes&&ue(function(e){return e.innerHTML="",e.firstChild.setAttribute("value",""),""===e.firstChild.getAttribute("value")})||le("value",function(e,t,n){if(!n&&"input"===e.nodeName.toLowerCase())return e.defaultValue}),ue(function(e){return null==e.getAttribute("disabled")})||le(P,function(e,t,n){var r;if(!n)return!0===e[t]?t.toLowerCase():(r=e.getAttributeNode(t))&&r.specified?r.value:null}),oe}(e);w.find=E,w.expr=E.selectors,w.expr[":"]=w.expr.pseudos,w.uniqueSort=w.unique=E.uniqueSort,w.text=E.getText,w.isXMLDoc=E.isXML,w.contains=E.contains,w.escapeSelector=E.escape;var k=function(e,t,n){var r=[],i=void 0!==n;while((e=e[t])&&9!==e.nodeType)if(1===e.nodeType){if(i&&w(e).is(n))break;r.push(e)}return r},S=function(e,t){for(var n=[];e;e=e.nextSibling)1===e.nodeType&&e!==t&&n.push(e);return n},D=w.expr.match.needsContext;function N(e,t){return e.nodeName&&e.nodeName.toLowerCase()===t.toLowerCase()}var A=/^<([a-z][^\/\0>:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i;function j(e,t,n){return g(t)?w.grep(e,function(e,r){return!!t.call(e,r,e)!==n}):t.nodeType?w.grep(e,function(e){return e===t!==n}):"string"!=typeof t?w.grep(e,function(e){return u.call(t,e)>-1!==n}):w.filter(t,e,n)}w.filter=function(e,t,n){var r=t[0];return n&&(e=":not("+e+")"),1===t.length&&1===r.nodeType?w.find.matchesSelector(r,e)?[r]:[]:w.find.matches(e,w.grep(t,function(e){return 1===e.nodeType}))},w.fn.extend({find:function(e){var t,n,r=this.length,i=this;if("string"!=typeof e)return this.pushStack(w(e).filter(function(){for(t=0;t1?w.uniqueSort(n):n},filter:function(e){return this.pushStack(j(this,e||[],!1))},not:function(e){return this.pushStack(j(this,e||[],!0))},is:function(e){return!!j(this,"string"==typeof e&&D.test(e)?w(e):e||[],!1).length}});var q,L=/^(?:\s*(<[\w\W]+>)[^>]*|#([\w-]+))$/;(w.fn.init=function(e,t,n){var i,o;if(!e)return this;if(n=n||q,"string"==typeof e){if(!(i="<"===e[0]&&">"===e[e.length-1]&&e.length>=3?[null,e,null]:L.exec(e))||!i[1]&&t)return!t||t.jquery?(t||n).find(e):this.constructor(t).find(e);if(i[1]){if(t=t instanceof w?t[0]:t,w.merge(this,w.parseHTML(i[1],t&&t.nodeType?t.ownerDocument||t:r,!0)),A.test(i[1])&&w.isPlainObject(t))for(i in t)g(this[i])?this[i](t[i]):this.attr(i,t[i]);return this}return(o=r.getElementById(i[2]))&&(this[0]=o,this.length=1),this}return e.nodeType?(this[0]=e,this.length=1,this):g(e)?void 0!==n.ready?n.ready(e):e(w):w.makeArray(e,this)}).prototype=w.fn,q=w(r);var H=/^(?:parents|prev(?:Until|All))/,O={children:!0,contents:!0,next:!0,prev:!0};w.fn.extend({has:function(e){var t=w(e,this),n=t.length;return this.filter(function(){for(var e=0;e-1:1===n.nodeType&&w.find.matchesSelector(n,e))){o.push(n);break}return this.pushStack(o.length>1?w.uniqueSort(o):o)},index:function(e){return e?"string"==typeof e?u.call(w(e),this[0]):u.call(this,e.jquery?e[0]:e):this[0]&&this[0].parentNode?this.first().prevAll().length:-1},add:function(e,t){return this.pushStack(w.uniqueSort(w.merge(this.get(),w(e,t))))},addBack:function(e){return this.add(null==e?this.prevObject:this.prevObject.filter(e))}});function P(e,t){while((e=e[t])&&1!==e.nodeType);return e}w.each({parent:function(e){var t=e.parentNode;return t&&11!==t.nodeType?t:null},parents:function(e){return k(e,"parentNode")},parentsUntil:function(e,t,n){return k(e,"parentNode",n)},next:function(e){return P(e,"nextSibling")},prev:function(e){return P(e,"previousSibling")},nextAll:function(e){return k(e,"nextSibling")},prevAll:function(e){return k(e,"previousSibling")},nextUntil:function(e,t,n){return k(e,"nextSibling",n)},prevUntil:function(e,t,n){return k(e,"previousSibling",n)},siblings:function(e){return S((e.parentNode||{}).firstChild,e)},children:function(e){return S(e.firstChild)},contents:function(e){return N(e,"iframe")?e.contentDocument:(N(e,"template")&&(e=e.content||e),w.merge([],e.childNodes))}},function(e,t){w.fn[e]=function(n,r){var i=w.map(this,t,n);return"Until"!==e.slice(-5)&&(r=n),r&&"string"==typeof r&&(i=w.filter(r,i)),this.length>1&&(O[e]||w.uniqueSort(i),H.test(e)&&i.reverse()),this.pushStack(i)}});var M=/[^\x20\t\r\n\f]+/g;function R(e){var t={};return w.each(e.match(M)||[],function(e,n){t[n]=!0}),t}w.Callbacks=function(e){e="string"==typeof e?R(e):w.extend({},e);var t,n,r,i,o=[],a=[],s=-1,u=function(){for(i=i||e.once,r=t=!0;a.length;s=-1){n=a.shift();while(++s-1)o.splice(n,1),n<=s&&s--}),this},has:function(e){return e?w.inArray(e,o)>-1:o.length>0},empty:function(){return o&&(o=[]),this},disable:function(){return i=a=[],o=n="",this},disabled:function(){return!o},lock:function(){return i=a=[],n||t||(o=n=""),this},locked:function(){return!!i},fireWith:function(e,n){return i||(n=[e,(n=n||[]).slice?n.slice():n],a.push(n),t||u()),this},fire:function(){return l.fireWith(this,arguments),this},fired:function(){return!!r}};return l};function I(e){return e}function W(e){throw e}function $(e,t,n,r){var i;try{e&&g(i=e.promise)?i.call(e).done(t).fail(n):e&&g(i=e.then)?i.call(e,t,n):t.apply(void 0,[e].slice(r))}catch(e){n.apply(void 0,[e])}}w.extend({Deferred:function(t){var n=[["notify","progress",w.Callbacks("memory"),w.Callbacks("memory"),2],["resolve","done",w.Callbacks("once memory"),w.Callbacks("once memory"),0,"resolved"],["reject","fail",w.Callbacks("once memory"),w.Callbacks("once memory"),1,"rejected"]],r="pending",i={state:function(){return r},always:function(){return o.done(arguments).fail(arguments),this},"catch":function(e){return i.then(null,e)},pipe:function(){var e=arguments;return w.Deferred(function(t){w.each(n,function(n,r){var i=g(e[r[4]])&&e[r[4]];o[r[1]](function(){var e=i&&i.apply(this,arguments);e&&g(e.promise)?e.promise().progress(t.notify).done(t.resolve).fail(t.reject):t[r[0]+"With"](this,i?[e]:arguments)})}),e=null}).promise()},then:function(t,r,i){var o=0;function a(t,n,r,i){return function(){var s=this,u=arguments,l=function(){var e,l;if(!(t=o&&(r!==W&&(s=void 0,u=[e]),n.rejectWith(s,u))}};t?c():(w.Deferred.getStackHook&&(c.stackTrace=w.Deferred.getStackHook()),e.setTimeout(c))}}return w.Deferred(function(e){n[0][3].add(a(0,e,g(i)?i:I,e.notifyWith)),n[1][3].add(a(0,e,g(t)?t:I)),n[2][3].add(a(0,e,g(r)?r:W))}).promise()},promise:function(e){return null!=e?w.extend(e,i):i}},o={};return w.each(n,function(e,t){var a=t[2],s=t[5];i[t[1]]=a.add,s&&a.add(function(){r=s},n[3-e][2].disable,n[3-e][3].disable,n[0][2].lock,n[0][3].lock),a.add(t[3].fire),o[t[0]]=function(){return o[t[0]+"With"](this===o?void 0:this,arguments),this},o[t[0]+"With"]=a.fireWith}),i.promise(o),t&&t.call(o,o),o},when:function(e){var t=arguments.length,n=t,r=Array(n),i=o.call(arguments),a=w.Deferred(),s=function(e){return function(n){r[e]=this,i[e]=arguments.length>1?o.call(arguments):n,--t||a.resolveWith(r,i)}};if(t<=1&&($(e,a.done(s(n)).resolve,a.reject,!t),"pending"===a.state()||g(i[n]&&i[n].then)))return a.then();while(n--)$(i[n],s(n),a.reject);return a.promise()}});var B=/^(Eval|Internal|Range|Reference|Syntax|Type|URI)Error$/;w.Deferred.exceptionHook=function(t,n){e.console&&e.console.warn&&t&&B.test(t.name)&&e.console.warn("jQuery.Deferred exception: "+t.message,t.stack,n)},w.readyException=function(t){e.setTimeout(function(){throw t})};var F=w.Deferred();w.fn.ready=function(e){return F.then(e)["catch"](function(e){w.readyException(e)}),this},w.extend({isReady:!1,readyWait:1,ready:function(e){(!0===e?--w.readyWait:w.isReady)||(w.isReady=!0,!0!==e&&--w.readyWait>0||F.resolveWith(r,[w]))}}),w.ready.then=F.then;function _(){r.removeEventListener("DOMContentLoaded",_),e.removeEventListener("load",_),w.ready()}"complete"===r.readyState||"loading"!==r.readyState&&!r.documentElement.doScroll?e.setTimeout(w.ready):(r.addEventListener("DOMContentLoaded",_),e.addEventListener("load",_));var z=function(e,t,n,r,i,o,a){var s=0,u=e.length,l=null==n;if("object"===x(n)){i=!0;for(s in n)z(e,t,s,n[s],!0,o,a)}else if(void 0!==r&&(i=!0,g(r)||(a=!0),l&&(a?(t.call(e,r),t=null):(l=t,t=function(e,t,n){return l.call(w(e),n)})),t))for(;s1,null,!0)},removeData:function(e){return this.each(function(){K.remove(this,e)})}}),w.extend({queue:function(e,t,n){var r;if(e)return t=(t||"fx")+"queue",r=J.get(e,t),n&&(!r||Array.isArray(n)?r=J.access(e,t,w.makeArray(n)):r.push(n)),r||[]},dequeue:function(e,t){t=t||"fx";var n=w.queue(e,t),r=n.length,i=n.shift(),o=w._queueHooks(e,t),a=function(){w.dequeue(e,t)};"inprogress"===i&&(i=n.shift(),r--),i&&("fx"===t&&n.unshift("inprogress"),delete o.stop,i.call(e,a,o)),!r&&o&&o.empty.fire()},_queueHooks:function(e,t){var n=t+"queueHooks";return J.get(e,n)||J.access(e,n,{empty:w.Callbacks("once memory").add(function(){J.remove(e,[t+"queue",n])})})}}),w.fn.extend({queue:function(e,t){var n=2;return"string"!=typeof e&&(t=e,e="fx",n--),arguments.length\x20\t\r\n\f]+)/i,he=/^$|^module$|\/(?:java|ecma)script/i,ge={option:[1,""],thead:[1,"

","
"],col:[2,"","
"],tr:[2,"","
"],td:[3,"","
"],_default:[0,"",""]};ge.optgroup=ge.option,ge.tbody=ge.tfoot=ge.colgroup=ge.caption=ge.thead,ge.th=ge.td;function ye(e,t){var n;return n="undefined"!=typeof e.getElementsByTagName?e.getElementsByTagName(t||"*"):"undefined"!=typeof e.querySelectorAll?e.querySelectorAll(t||"*"):[],void 0===t||t&&N(e,t)?w.merge([e],n):n}function ve(e,t){for(var n=0,r=e.length;n-1)i&&i.push(o);else if(l=w.contains(o.ownerDocument,o),a=ye(f.appendChild(o),"script"),l&&ve(a),n){c=0;while(o=a[c++])he.test(o.type||"")&&n.push(o)}return f}!function(){var e=r.createDocumentFragment().appendChild(r.createElement("div")),t=r.createElement("input");t.setAttribute("type","radio"),t.setAttribute("checked","checked"),t.setAttribute("name","t"),e.appendChild(t),h.checkClone=e.cloneNode(!0).cloneNode(!0).lastChild.checked,e.innerHTML="",h.noCloneChecked=!!e.cloneNode(!0).lastChild.defaultValue}();var be=r.documentElement,we=/^key/,Te=/^(?:mouse|pointer|contextmenu|drag|drop)|click/,Ce=/^([^.]*)(?:\.(.+)|)/;function Ee(){return!0}function ke(){return!1}function Se(){try{return r.activeElement}catch(e){}}function De(e,t,n,r,i,o){var a,s;if("object"==typeof t){"string"!=typeof n&&(r=r||n,n=void 0);for(s in t)De(e,s,n,r,t[s],o);return e}if(null==r&&null==i?(i=n,r=n=void 0):null==i&&("string"==typeof n?(i=r,r=void 0):(i=r,r=n,n=void 0)),!1===i)i=ke;else if(!i)return e;return 1===o&&(a=i,(i=function(e){return w().off(e),a.apply(this,arguments)}).guid=a.guid||(a.guid=w.guid++)),e.each(function(){w.event.add(this,t,i,r,n)})}w.event={global:{},add:function(e,t,n,r,i){var o,a,s,u,l,c,f,p,d,h,g,y=J.get(e);if(y){n.handler&&(n=(o=n).handler,i=o.selector),i&&w.find.matchesSelector(be,i),n.guid||(n.guid=w.guid++),(u=y.events)||(u=y.events={}),(a=y.handle)||(a=y.handle=function(t){return"undefined"!=typeof w&&w.event.triggered!==t.type?w.event.dispatch.apply(e,arguments):void 0}),l=(t=(t||"").match(M)||[""]).length;while(l--)d=g=(s=Ce.exec(t[l])||[])[1],h=(s[2]||"").split(".").sort(),d&&(f=w.event.special[d]||{},d=(i?f.delegateType:f.bindType)||d,f=w.event.special[d]||{},c=w.extend({type:d,origType:g,data:r,handler:n,guid:n.guid,selector:i,needsContext:i&&w.expr.match.needsContext.test(i),namespace:h.join(".")},o),(p=u[d])||((p=u[d]=[]).delegateCount=0,f.setup&&!1!==f.setup.call(e,r,h,a)||e.addEventListener&&e.addEventListener(d,a)),f.add&&(f.add.call(e,c),c.handler.guid||(c.handler.guid=n.guid)),i?p.splice(p.delegateCount++,0,c):p.push(c),w.event.global[d]=!0)}},remove:function(e,t,n,r,i){var o,a,s,u,l,c,f,p,d,h,g,y=J.hasData(e)&&J.get(e);if(y&&(u=y.events)){l=(t=(t||"").match(M)||[""]).length;while(l--)if(s=Ce.exec(t[l])||[],d=g=s[1],h=(s[2]||"").split(".").sort(),d){f=w.event.special[d]||{},p=u[d=(r?f.delegateType:f.bindType)||d]||[],s=s[2]&&new RegExp("(^|\\.)"+h.join("\\.(?:.*\\.|)")+"(\\.|$)"),a=o=p.length;while(o--)c=p[o],!i&&g!==c.origType||n&&n.guid!==c.guid||s&&!s.test(c.namespace)||r&&r!==c.selector&&("**"!==r||!c.selector)||(p.splice(o,1),c.selector&&p.delegateCount--,f.remove&&f.remove.call(e,c));a&&!p.length&&(f.teardown&&!1!==f.teardown.call(e,h,y.handle)||w.removeEvent(e,d,y.handle),delete u[d])}else for(d in u)w.event.remove(e,d+t[l],n,r,!0);w.isEmptyObject(u)&&J.remove(e,"handle events")}},dispatch:function(e){var t=w.event.fix(e),n,r,i,o,a,s,u=new Array(arguments.length),l=(J.get(this,"events")||{})[t.type]||[],c=w.event.special[t.type]||{};for(u[0]=t,n=1;n=1))for(;l!==this;l=l.parentNode||this)if(1===l.nodeType&&("click"!==e.type||!0!==l.disabled)){for(o=[],a={},n=0;n-1:w.find(i,this,null,[l]).length),a[i]&&o.push(r);o.length&&s.push({elem:l,handlers:o})}return l=this,u\x20\t\r\n\f]*)[^>]*)\/>/gi,Ae=/\s*$/g;function Le(e,t){return N(e,"table")&&N(11!==t.nodeType?t:t.firstChild,"tr")?w(e).children("tbody")[0]||e:e}function He(e){return e.type=(null!==e.getAttribute("type"))+"/"+e.type,e}function Oe(e){return"true/"===(e.type||"").slice(0,5)?e.type=e.type.slice(5):e.removeAttribute("type"),e}function Pe(e,t){var n,r,i,o,a,s,u,l;if(1===t.nodeType){if(J.hasData(e)&&(o=J.access(e),a=J.set(t,o),l=o.events)){delete a.handle,a.events={};for(i in l)for(n=0,r=l[i].length;n1&&"string"==typeof y&&!h.checkClone&&je.test(y))return e.each(function(i){var o=e.eq(i);v&&(t[0]=y.call(this,i,o.html())),Re(o,t,n,r)});if(p&&(i=xe(t,e[0].ownerDocument,!1,e,r),o=i.firstChild,1===i.childNodes.length&&(i=o),o||r)){for(u=(s=w.map(ye(i,"script"),He)).length;f")},clone:function(e,t,n){var r,i,o,a,s=e.cloneNode(!0),u=w.contains(e.ownerDocument,e);if(!(h.noCloneChecked||1!==e.nodeType&&11!==e.nodeType||w.isXMLDoc(e)))for(a=ye(s),r=0,i=(o=ye(e)).length;r0&&ve(a,!u&&ye(e,"script")),s},cleanData:function(e){for(var t,n,r,i=w.event.special,o=0;void 0!==(n=e[o]);o++)if(Y(n)){if(t=n[J.expando]){if(t.events)for(r in t.events)i[r]?w.event.remove(n,r):w.removeEvent(n,r,t.handle);n[J.expando]=void 0}n[K.expando]&&(n[K.expando]=void 0)}}}),w.fn.extend({detach:function(e){return Ie(this,e,!0)},remove:function(e){return Ie(this,e)},text:function(e){return z(this,function(e){return void 0===e?w.text(this):this.empty().each(function(){1!==this.nodeType&&11!==this.nodeType&&9!==this.nodeType||(this.textContent=e)})},null,e,arguments.length)},append:function(){return Re(this,arguments,function(e){1!==this.nodeType&&11!==this.nodeType&&9!==this.nodeType||Le(this,e).appendChild(e)})},prepend:function(){return Re(this,arguments,function(e){if(1===this.nodeType||11===this.nodeType||9===this.nodeType){var t=Le(this,e);t.insertBefore(e,t.firstChild)}})},before:function(){return Re(this,arguments,function(e){this.parentNode&&this.parentNode.insertBefore(e,this)})},after:function(){return Re(this,arguments,function(e){this.parentNode&&this.parentNode.insertBefore(e,this.nextSibling)})},empty:function(){for(var e,t=0;null!=(e=this[t]);t++)1===e.nodeType&&(w.cleanData(ye(e,!1)),e.textContent="");return this},clone:function(e,t){return e=null!=e&&e,t=null==t?e:t,this.map(function(){return w.clone(this,e,t)})},html:function(e){return z(this,function(e){var t=this[0]||{},n=0,r=this.length;if(void 0===e&&1===t.nodeType)return t.innerHTML;if("string"==typeof e&&!Ae.test(e)&&!ge[(de.exec(e)||["",""])[1].toLowerCase()]){e=w.htmlPrefilter(e);try{for(;n=0&&(u+=Math.max(0,Math.ceil(e["offset"+t[0].toUpperCase()+t.slice(1)]-o-u-s-.5))),u}function et(e,t,n){var r=$e(e),i=Fe(e,t,r),o="border-box"===w.css(e,"boxSizing",!1,r),a=o;if(We.test(i)){if(!n)return i;i="auto"}return a=a&&(h.boxSizingReliable()||i===e.style[t]),("auto"===i||!parseFloat(i)&&"inline"===w.css(e,"display",!1,r))&&(i=e["offset"+t[0].toUpperCase()+t.slice(1)],a=!0),(i=parseFloat(i)||0)+Ze(e,t,n||(o?"border":"content"),a,r,i)+"px"}w.extend({cssHooks:{opacity:{get:function(e,t){if(t){var n=Fe(e,"opacity");return""===n?"1":n}}}},cssNumber:{animationIterationCount:!0,columnCount:!0,fillOpacity:!0,flexGrow:!0,flexShrink:!0,fontWeight:!0,lineHeight:!0,opacity:!0,order:!0,orphans:!0,widows:!0,zIndex:!0,zoom:!0},cssProps:{},style:function(e,t,n,r){if(e&&3!==e.nodeType&&8!==e.nodeType&&e.style){var i,o,a,s=G(t),u=Xe.test(t),l=e.style;if(u||(t=Je(s)),a=w.cssHooks[t]||w.cssHooks[s],void 0===n)return a&&"get"in a&&void 0!==(i=a.get(e,!1,r))?i:l[t];"string"==(o=typeof n)&&(i=ie.exec(n))&&i[1]&&(n=ue(e,t,i),o="number"),null!=n&&n===n&&("number"===o&&(n+=i&&i[3]||(w.cssNumber[s]?"":"px")),h.clearCloneStyle||""!==n||0!==t.indexOf("background")||(l[t]="inherit"),a&&"set"in a&&void 0===(n=a.set(e,n,r))||(u?l.setProperty(t,n):l[t]=n))}},css:function(e,t,n,r){var i,o,a,s=G(t);return Xe.test(t)||(t=Je(s)),(a=w.cssHooks[t]||w.cssHooks[s])&&"get"in a&&(i=a.get(e,!0,n)),void 0===i&&(i=Fe(e,t,r)),"normal"===i&&t in Ve&&(i=Ve[t]),""===n||n?(o=parseFloat(i),!0===n||isFinite(o)?o||0:i):i}}),w.each(["height","width"],function(e,t){w.cssHooks[t]={get:function(e,n,r){if(n)return!ze.test(w.css(e,"display"))||e.getClientRects().length&&e.getBoundingClientRect().width?et(e,t,r):se(e,Ue,function(){return et(e,t,r)})},set:function(e,n,r){var i,o=$e(e),a="border-box"===w.css(e,"boxSizing",!1,o),s=r&&Ze(e,t,r,a,o);return a&&h.scrollboxSize()===o.position&&(s-=Math.ceil(e["offset"+t[0].toUpperCase()+t.slice(1)]-parseFloat(o[t])-Ze(e,t,"border",!1,o)-.5)),s&&(i=ie.exec(n))&&"px"!==(i[3]||"px")&&(e.style[t]=n,n=w.css(e,t)),Ke(e,n,s)}}}),w.cssHooks.marginLeft=_e(h.reliableMarginLeft,function(e,t){if(t)return(parseFloat(Fe(e,"marginLeft"))||e.getBoundingClientRect().left-se(e,{marginLeft:0},function(){return e.getBoundingClientRect().left}))+"px"}),w.each({margin:"",padding:"",border:"Width"},function(e,t){w.cssHooks[e+t]={expand:function(n){for(var r=0,i={},o="string"==typeof n?n.split(" "):[n];r<4;r++)i[e+oe[r]+t]=o[r]||o[r-2]||o[0];return i}},"margin"!==e&&(w.cssHooks[e+t].set=Ke)}),w.fn.extend({css:function(e,t){return z(this,function(e,t,n){var r,i,o={},a=0;if(Array.isArray(t)){for(r=$e(e),i=t.length;a1)}});function tt(e,t,n,r,i){return new tt.prototype.init(e,t,n,r,i)}w.Tween=tt,tt.prototype={constructor:tt,init:function(e,t,n,r,i,o){this.elem=e,this.prop=n,this.easing=i||w.easing._default,this.options=t,this.start=this.now=this.cur(),this.end=r,this.unit=o||(w.cssNumber[n]?"":"px")},cur:function(){var e=tt.propHooks[this.prop];return e&&e.get?e.get(this):tt.propHooks._default.get(this)},run:function(e){var t,n=tt.propHooks[this.prop];return this.options.duration?this.pos=t=w.easing[this.easing](e,this.options.duration*e,0,1,this.options.duration):this.pos=t=e,this.now=(this.end-this.start)*t+this.start,this.options.step&&this.options.step.call(this.elem,this.now,this),n&&n.set?n.set(this):tt.propHooks._default.set(this),this}},tt.prototype.init.prototype=tt.prototype,tt.propHooks={_default:{get:function(e){var t;return 1!==e.elem.nodeType||null!=e.elem[e.prop]&&null==e.elem.style[e.prop]?e.elem[e.prop]:(t=w.css(e.elem,e.prop,""))&&"auto"!==t?t:0},set:function(e){w.fx.step[e.prop]?w.fx.step[e.prop](e):1!==e.elem.nodeType||null==e.elem.style[w.cssProps[e.prop]]&&!w.cssHooks[e.prop]?e.elem[e.prop]=e.now:w.style(e.elem,e.prop,e.now+e.unit)}}},tt.propHooks.scrollTop=tt.propHooks.scrollLeft={set:function(e){e.elem.nodeType&&e.elem.parentNode&&(e.elem[e.prop]=e.now)}},w.easing={linear:function(e){return e},swing:function(e){return.5-Math.cos(e*Math.PI)/2},_default:"swing"},w.fx=tt.prototype.init,w.fx.step={};var nt,rt,it=/^(?:toggle|show|hide)$/,ot=/queueHooks$/;function at(){rt&&(!1===r.hidden&&e.requestAnimationFrame?e.requestAnimationFrame(at):e.setTimeout(at,w.fx.interval),w.fx.tick())}function st(){return e.setTimeout(function(){nt=void 0}),nt=Date.now()}function ut(e,t){var n,r=0,i={height:e};for(t=t?1:0;r<4;r+=2-t)i["margin"+(n=oe[r])]=i["padding"+n]=e;return t&&(i.opacity=i.width=e),i}function lt(e,t,n){for(var r,i=(pt.tweeners[t]||[]).concat(pt.tweeners["*"]),o=0,a=i.length;o1)},removeAttr:function(e){return this.each(function(){w.removeAttr(this,e)})}}),w.extend({attr:function(e,t,n){var r,i,o=e.nodeType;if(3!==o&&8!==o&&2!==o)return"undefined"==typeof e.getAttribute?w.prop(e,t,n):(1===o&&w.isXMLDoc(e)||(i=w.attrHooks[t.toLowerCase()]||(w.expr.match.bool.test(t)?dt:void 0)),void 0!==n?null===n?void w.removeAttr(e,t):i&&"set"in i&&void 0!==(r=i.set(e,n,t))?r:(e.setAttribute(t,n+""),n):i&&"get"in i&&null!==(r=i.get(e,t))?r:null==(r=w.find.attr(e,t))?void 0:r)},attrHooks:{type:{set:function(e,t){if(!h.radioValue&&"radio"===t&&N(e,"input")){var n=e.value;return e.setAttribute("type",t),n&&(e.value=n),t}}}},removeAttr:function(e,t){var n,r=0,i=t&&t.match(M);if(i&&1===e.nodeType)while(n=i[r++])e.removeAttribute(n)}}),dt={set:function(e,t,n){return!1===t?w.removeAttr(e,n):e.setAttribute(n,n),n}},w.each(w.expr.match.bool.source.match(/\w+/g),function(e,t){var n=ht[t]||w.find.attr;ht[t]=function(e,t,r){var i,o,a=t.toLowerCase();return r||(o=ht[a],ht[a]=i,i=null!=n(e,t,r)?a:null,ht[a]=o),i}});var gt=/^(?:input|select|textarea|button)$/i,yt=/^(?:a|area)$/i;w.fn.extend({prop:function(e,t){return z(this,w.prop,e,t,arguments.length>1)},removeProp:function(e){return this.each(function(){delete this[w.propFix[e]||e]})}}),w.extend({prop:function(e,t,n){var r,i,o=e.nodeType;if(3!==o&&8!==o&&2!==o)return 1===o&&w.isXMLDoc(e)||(t=w.propFix[t]||t,i=w.propHooks[t]),void 0!==n?i&&"set"in i&&void 0!==(r=i.set(e,n,t))?r:e[t]=n:i&&"get"in i&&null!==(r=i.get(e,t))?r:e[t]},propHooks:{tabIndex:{get:function(e){var t=w.find.attr(e,"tabindex");return t?parseInt(t,10):gt.test(e.nodeName)||yt.test(e.nodeName)&&e.href?0:-1}}},propFix:{"for":"htmlFor","class":"className"}}),h.optSelected||(w.propHooks.selected={get:function(e){var t=e.parentNode;return t&&t.parentNode&&t.parentNode.selectedIndex,null},set:function(e){var t=e.parentNode;t&&(t.selectedIndex,t.parentNode&&t.parentNode.selectedIndex)}}),w.each(["tabIndex","readOnly","maxLength","cellSpacing","cellPadding","rowSpan","colSpan","useMap","frameBorder","contentEditable"],function(){w.propFix[this.toLowerCase()]=this});function vt(e){return(e.match(M)||[]).join(" ")}function mt(e){return e.getAttribute&&e.getAttribute("class")||""}function xt(e){return Array.isArray(e)?e:"string"==typeof e?e.match(M)||[]:[]}w.fn.extend({addClass:function(e){var t,n,r,i,o,a,s,u=0;if(g(e))return this.each(function(t){w(this).addClass(e.call(this,t,mt(this)))});if((t=xt(e)).length)while(n=this[u++])if(i=mt(n),r=1===n.nodeType&&" "+vt(i)+" "){a=0;while(o=t[a++])r.indexOf(" "+o+" ")<0&&(r+=o+" ");i!==(s=vt(r))&&n.setAttribute("class",s)}return this},removeClass:function(e){var t,n,r,i,o,a,s,u=0;if(g(e))return this.each(function(t){w(this).removeClass(e.call(this,t,mt(this)))});if(!arguments.length)return this.attr("class","");if((t=xt(e)).length)while(n=this[u++])if(i=mt(n),r=1===n.nodeType&&" "+vt(i)+" "){a=0;while(o=t[a++])while(r.indexOf(" "+o+" ")>-1)r=r.replace(" "+o+" "," ");i!==(s=vt(r))&&n.setAttribute("class",s)}return this},toggleClass:function(e,t){var n=typeof e,r="string"===n||Array.isArray(e);return"boolean"==typeof t&&r?t?this.addClass(e):this.removeClass(e):g(e)?this.each(function(n){w(this).toggleClass(e.call(this,n,mt(this),t),t)}):this.each(function(){var t,i,o,a;if(r){i=0,o=w(this),a=xt(e);while(t=a[i++])o.hasClass(t)?o.removeClass(t):o.addClass(t)}else void 0!==e&&"boolean"!==n||((t=mt(this))&&J.set(this,"__className__",t),this.setAttribute&&this.setAttribute("class",t||!1===e?"":J.get(this,"__className__")||""))})},hasClass:function(e){var t,n,r=0;t=" "+e+" ";while(n=this[r++])if(1===n.nodeType&&(" "+vt(mt(n))+" ").indexOf(t)>-1)return!0;return!1}});var bt=/\r/g;w.fn.extend({val:function(e){var t,n,r,i=this[0];{if(arguments.length)return r=g(e),this.each(function(n){var i;1===this.nodeType&&(null==(i=r?e.call(this,n,w(this).val()):e)?i="":"number"==typeof i?i+="":Array.isArray(i)&&(i=w.map(i,function(e){return null==e?"":e+""})),(t=w.valHooks[this.type]||w.valHooks[this.nodeName.toLowerCase()])&&"set"in t&&void 0!==t.set(this,i,"value")||(this.value=i))});if(i)return(t=w.valHooks[i.type]||w.valHooks[i.nodeName.toLowerCase()])&&"get"in t&&void 0!==(n=t.get(i,"value"))?n:"string"==typeof(n=i.value)?n.replace(bt,""):null==n?"":n}}}),w.extend({valHooks:{option:{get:function(e){var t=w.find.attr(e,"value");return null!=t?t:vt(w.text(e))}},select:{get:function(e){var t,n,r,i=e.options,o=e.selectedIndex,a="select-one"===e.type,s=a?null:[],u=a?o+1:i.length;for(r=o<0?u:a?o:0;r-1)&&(n=!0);return n||(e.selectedIndex=-1),o}}}}),w.each(["radio","checkbox"],function(){w.valHooks[this]={set:function(e,t){if(Array.isArray(t))return e.checked=w.inArray(w(e).val(),t)>-1}},h.checkOn||(w.valHooks[this].get=function(e){return null===e.getAttribute("value")?"on":e.value})}),h.focusin="onfocusin"in e;var wt=/^(?:focusinfocus|focusoutblur)$/,Tt=function(e){e.stopPropagation()};w.extend(w.event,{trigger:function(t,n,i,o){var a,s,u,l,c,p,d,h,v=[i||r],m=f.call(t,"type")?t.type:t,x=f.call(t,"namespace")?t.namespace.split("."):[];if(s=h=u=i=i||r,3!==i.nodeType&&8!==i.nodeType&&!wt.test(m+w.event.triggered)&&(m.indexOf(".")>-1&&(m=(x=m.split(".")).shift(),x.sort()),c=m.indexOf(":")<0&&"on"+m,t=t[w.expando]?t:new w.Event(m,"object"==typeof t&&t),t.isTrigger=o?2:3,t.namespace=x.join("."),t.rnamespace=t.namespace?new RegExp("(^|\\.)"+x.join("\\.(?:.*\\.|)")+"(\\.|$)"):null,t.result=void 0,t.target||(t.target=i),n=null==n?[t]:w.makeArray(n,[t]),d=w.event.special[m]||{},o||!d.trigger||!1!==d.trigger.apply(i,n))){if(!o&&!d.noBubble&&!y(i)){for(l=d.delegateType||m,wt.test(l+m)||(s=s.parentNode);s;s=s.parentNode)v.push(s),u=s;u===(i.ownerDocument||r)&&v.push(u.defaultView||u.parentWindow||e)}a=0;while((s=v[a++])&&!t.isPropagationStopped())h=s,t.type=a>1?l:d.bindType||m,(p=(J.get(s,"events")||{})[t.type]&&J.get(s,"handle"))&&p.apply(s,n),(p=c&&s[c])&&p.apply&&Y(s)&&(t.result=p.apply(s,n),!1===t.result&&t.preventDefault());return t.type=m,o||t.isDefaultPrevented()||d._default&&!1!==d._default.apply(v.pop(),n)||!Y(i)||c&&g(i[m])&&!y(i)&&((u=i[c])&&(i[c]=null),w.event.triggered=m,t.isPropagationStopped()&&h.addEventListener(m,Tt),i[m](),t.isPropagationStopped()&&h.removeEventListener(m,Tt),w.event.triggered=void 0,u&&(i[c]=u)),t.result}},simulate:function(e,t,n){var r=w.extend(new w.Event,n,{type:e,isSimulated:!0});w.event.trigger(r,null,t)}}),w.fn.extend({trigger:function(e,t){return this.each(function(){w.event.trigger(e,t,this)})},triggerHandler:function(e,t){var n=this[0];if(n)return w.event.trigger(e,t,n,!0)}}),h.focusin||w.each({focus:"focusin",blur:"focusout"},function(e,t){var n=function(e){w.event.simulate(t,e.target,w.event.fix(e))};w.event.special[t]={setup:function(){var r=this.ownerDocument||this,i=J.access(r,t);i||r.addEventListener(e,n,!0),J.access(r,t,(i||0)+1)},teardown:function(){var r=this.ownerDocument||this,i=J.access(r,t)-1;i?J.access(r,t,i):(r.removeEventListener(e,n,!0),J.remove(r,t))}}});var Ct=e.location,Et=Date.now(),kt=/\?/;w.parseXML=function(t){var n;if(!t||"string"!=typeof t)return null;try{n=(new e.DOMParser).parseFromString(t,"text/xml")}catch(e){n=void 0}return n&&!n.getElementsByTagName("parsererror").length||w.error("Invalid XML: "+t),n};var St=/\[\]$/,Dt=/\r?\n/g,Nt=/^(?:submit|button|image|reset|file)$/i,At=/^(?:input|select|textarea|keygen)/i;function jt(e,t,n,r){var i;if(Array.isArray(t))w.each(t,function(t,i){n||St.test(e)?r(e,i):jt(e+"["+("object"==typeof i&&null!=i?t:"")+"]",i,n,r)});else if(n||"object"!==x(t))r(e,t);else for(i in t)jt(e+"["+i+"]",t[i],n,r)}w.param=function(e,t){var n,r=[],i=function(e,t){var n=g(t)?t():t;r[r.length]=encodeURIComponent(e)+"="+encodeURIComponent(null==n?"":n)};if(Array.isArray(e)||e.jquery&&!w.isPlainObject(e))w.each(e,function(){i(this.name,this.value)});else for(n in e)jt(n,e[n],t,i);return r.join("&")},w.fn.extend({serialize:function(){return w.param(this.serializeArray())},serializeArray:function(){return this.map(function(){var e=w.prop(this,"elements");return e?w.makeArray(e):this}).filter(function(){var e=this.type;return this.name&&!w(this).is(":disabled")&&At.test(this.nodeName)&&!Nt.test(e)&&(this.checked||!pe.test(e))}).map(function(e,t){var n=w(this).val();return null==n?null:Array.isArray(n)?w.map(n,function(e){return{name:t.name,value:e.replace(Dt,"\r\n")}}):{name:t.name,value:n.replace(Dt,"\r\n")}}).get()}});var qt=/%20/g,Lt=/#.*$/,Ht=/([?&])_=[^&]*/,Ot=/^(.*?):[ \t]*([^\r\n]*)$/gm,Pt=/^(?:about|app|app-storage|.+-extension|file|res|widget):$/,Mt=/^(?:GET|HEAD)$/,Rt=/^\/\//,It={},Wt={},$t="*/".concat("*"),Bt=r.createElement("a");Bt.href=Ct.href;function Ft(e){return function(t,n){"string"!=typeof t&&(n=t,t="*");var r,i=0,o=t.toLowerCase().match(M)||[];if(g(n))while(r=o[i++])"+"===r[0]?(r=r.slice(1)||"*",(e[r]=e[r]||[]).unshift(n)):(e[r]=e[r]||[]).push(n)}}function _t(e,t,n,r){var i={},o=e===Wt;function a(s){var u;return i[s]=!0,w.each(e[s]||[],function(e,s){var l=s(t,n,r);return"string"!=typeof l||o||i[l]?o?!(u=l):void 0:(t.dataTypes.unshift(l),a(l),!1)}),u}return a(t.dataTypes[0])||!i["*"]&&a("*")}function zt(e,t){var n,r,i=w.ajaxSettings.flatOptions||{};for(n in t)void 0!==t[n]&&((i[n]?e:r||(r={}))[n]=t[n]);return r&&w.extend(!0,e,r),e}function Xt(e,t,n){var r,i,o,a,s=e.contents,u=e.dataTypes;while("*"===u[0])u.shift(),void 0===r&&(r=e.mimeType||t.getResponseHeader("Content-Type"));if(r)for(i in s)if(s[i]&&s[i].test(r)){u.unshift(i);break}if(u[0]in n)o=u[0];else{for(i in n){if(!u[0]||e.converters[i+" "+u[0]]){o=i;break}a||(a=i)}o=o||a}if(o)return o!==u[0]&&u.unshift(o),n[o]}function Ut(e,t,n,r){var i,o,a,s,u,l={},c=e.dataTypes.slice();if(c[1])for(a in e.converters)l[a.toLowerCase()]=e.converters[a];o=c.shift();while(o)if(e.responseFields[o]&&(n[e.responseFields[o]]=t),!u&&r&&e.dataFilter&&(t=e.dataFilter(t,e.dataType)),u=o,o=c.shift())if("*"===o)o=u;else if("*"!==u&&u!==o){if(!(a=l[u+" "+o]||l["* "+o]))for(i in l)if((s=i.split(" "))[1]===o&&(a=l[u+" "+s[0]]||l["* "+s[0]])){!0===a?a=l[i]:!0!==l[i]&&(o=s[0],c.unshift(s[1]));break}if(!0!==a)if(a&&e["throws"])t=a(t);else try{t=a(t)}catch(e){return{state:"parsererror",error:a?e:"No conversion from "+u+" to "+o}}}return{state:"success",data:t}}w.extend({active:0,lastModified:{},etag:{},ajaxSettings:{url:Ct.href,type:"GET",isLocal:Pt.test(Ct.protocol),global:!0,processData:!0,async:!0,contentType:"application/x-www-form-urlencoded; charset=UTF-8",accepts:{"*":$t,text:"text/plain",html:"text/html",xml:"application/xml, text/xml",json:"application/json, text/javascript"},contents:{xml:/\bxml\b/,html:/\bhtml/,json:/\bjson\b/},responseFields:{xml:"responseXML",text:"responseText",json:"responseJSON"},converters:{"* text":String,"text html":!0,"text json":JSON.parse,"text xml":w.parseXML},flatOptions:{url:!0,context:!0}},ajaxSetup:function(e,t){return t?zt(zt(e,w.ajaxSettings),t):zt(w.ajaxSettings,e)},ajaxPrefilter:Ft(It),ajaxTransport:Ft(Wt),ajax:function(t,n){"object"==typeof t&&(n=t,t=void 0),n=n||{};var i,o,a,s,u,l,c,f,p,d,h=w.ajaxSetup({},n),g=h.context||h,y=h.context&&(g.nodeType||g.jquery)?w(g):w.event,v=w.Deferred(),m=w.Callbacks("once memory"),x=h.statusCode||{},b={},T={},C="canceled",E={readyState:0,getResponseHeader:function(e){var t;if(c){if(!s){s={};while(t=Ot.exec(a))s[t[1].toLowerCase()]=t[2]}t=s[e.toLowerCase()]}return null==t?null:t},getAllResponseHeaders:function(){return c?a:null},setRequestHeader:function(e,t){return null==c&&(e=T[e.toLowerCase()]=T[e.toLowerCase()]||e,b[e]=t),this},overrideMimeType:function(e){return null==c&&(h.mimeType=e),this},statusCode:function(e){var t;if(e)if(c)E.always(e[E.status]);else for(t in e)x[t]=[x[t],e[t]];return this},abort:function(e){var t=e||C;return i&&i.abort(t),k(0,t),this}};if(v.promise(E),h.url=((t||h.url||Ct.href)+"").replace(Rt,Ct.protocol+"//"),h.type=n.method||n.type||h.method||h.type,h.dataTypes=(h.dataType||"*").toLowerCase().match(M)||[""],null==h.crossDomain){l=r.createElement("a");try{l.href=h.url,l.href=l.href,h.crossDomain=Bt.protocol+"//"+Bt.host!=l.protocol+"//"+l.host}catch(e){h.crossDomain=!0}}if(h.data&&h.processData&&"string"!=typeof h.data&&(h.data=w.param(h.data,h.traditional)),_t(It,h,n,E),c)return E;(f=w.event&&h.global)&&0==w.active++&&w.event.trigger("ajaxStart"),h.type=h.type.toUpperCase(),h.hasContent=!Mt.test(h.type),o=h.url.replace(Lt,""),h.hasContent?h.data&&h.processData&&0===(h.contentType||"").indexOf("application/x-www-form-urlencoded")&&(h.data=h.data.replace(qt,"+")):(d=h.url.slice(o.length),h.data&&(h.processData||"string"==typeof h.data)&&(o+=(kt.test(o)?"&":"?")+h.data,delete h.data),!1===h.cache&&(o=o.replace(Ht,"$1"),d=(kt.test(o)?"&":"?")+"_="+Et+++d),h.url=o+d),h.ifModified&&(w.lastModified[o]&&E.setRequestHeader("If-Modified-Since",w.lastModified[o]),w.etag[o]&&E.setRequestHeader("If-None-Match",w.etag[o])),(h.data&&h.hasContent&&!1!==h.contentType||n.contentType)&&E.setRequestHeader("Content-Type",h.contentType),E.setRequestHeader("Accept",h.dataTypes[0]&&h.accepts[h.dataTypes[0]]?h.accepts[h.dataTypes[0]]+("*"!==h.dataTypes[0]?", "+$t+"; q=0.01":""):h.accepts["*"]);for(p in h.headers)E.setRequestHeader(p,h.headers[p]);if(h.beforeSend&&(!1===h.beforeSend.call(g,E,h)||c))return E.abort();if(C="abort",m.add(h.complete),E.done(h.success),E.fail(h.error),i=_t(Wt,h,n,E)){if(E.readyState=1,f&&y.trigger("ajaxSend",[E,h]),c)return E;h.async&&h.timeout>0&&(u=e.setTimeout(function(){E.abort("timeout")},h.timeout));try{c=!1,i.send(b,k)}catch(e){if(c)throw e;k(-1,e)}}else k(-1,"No Transport");function k(t,n,r,s){var l,p,d,b,T,C=n;c||(c=!0,u&&e.clearTimeout(u),i=void 0,a=s||"",E.readyState=t>0?4:0,l=t>=200&&t<300||304===t,r&&(b=Xt(h,E,r)),b=Ut(h,b,E,l),l?(h.ifModified&&((T=E.getResponseHeader("Last-Modified"))&&(w.lastModified[o]=T),(T=E.getResponseHeader("etag"))&&(w.etag[o]=T)),204===t||"HEAD"===h.type?C="nocontent":304===t?C="notmodified":(C=b.state,p=b.data,l=!(d=b.error))):(d=C,!t&&C||(C="error",t<0&&(t=0))),E.status=t,E.statusText=(n||C)+"",l?v.resolveWith(g,[p,C,E]):v.rejectWith(g,[E,C,d]),E.statusCode(x),x=void 0,f&&y.trigger(l?"ajaxSuccess":"ajaxError",[E,h,l?p:d]),m.fireWith(g,[E,C]),f&&(y.trigger("ajaxComplete",[E,h]),--w.active||w.event.trigger("ajaxStop")))}return E},getJSON:function(e,t,n){return w.get(e,t,n,"json")},getScript:function(e,t){return w.get(e,void 0,t,"script")}}),w.each(["get","post"],function(e,t){w[t]=function(e,n,r,i){return g(n)&&(i=i||r,r=n,n=void 0),w.ajax(w.extend({url:e,type:t,dataType:i,data:n,success:r},w.isPlainObject(e)&&e))}}),w._evalUrl=function(e){return w.ajax({url:e,type:"GET",dataType:"script",cache:!0,async:!1,global:!1,"throws":!0})},w.fn.extend({wrapAll:function(e){var t;return this[0]&&(g(e)&&(e=e.call(this[0])),t=w(e,this[0].ownerDocument).eq(0).clone(!0),this[0].parentNode&&t.insertBefore(this[0]),t.map(function(){var e=this;while(e.firstElementChild)e=e.firstElementChild;return e}).append(this)),this},wrapInner:function(e){return g(e)?this.each(function(t){w(this).wrapInner(e.call(this,t))}):this.each(function(){var t=w(this),n=t.contents();n.length?n.wrapAll(e):t.append(e)})},wrap:function(e){var t=g(e);return this.each(function(n){w(this).wrapAll(t?e.call(this,n):e)})},unwrap:function(e){return this.parent(e).not("body").each(function(){w(this).replaceWith(this.childNodes)}),this}}),w.expr.pseudos.hidden=function(e){return!w.expr.pseudos.visible(e)},w.expr.pseudos.visible=function(e){return!!(e.offsetWidth||e.offsetHeight||e.getClientRects().length)},w.ajaxSettings.xhr=function(){try{return new e.XMLHttpRequest}catch(e){}};var Vt={0:200,1223:204},Gt=w.ajaxSettings.xhr();h.cors=!!Gt&&"withCredentials"in Gt,h.ajax=Gt=!!Gt,w.ajaxTransport(function(t){var n,r;if(h.cors||Gt&&!t.crossDomain)return{send:function(i,o){var a,s=t.xhr();if(s.open(t.type,t.url,t.async,t.username,t.password),t.xhrFields)for(a in t.xhrFields)s[a]=t.xhrFields[a];t.mimeType&&s.overrideMimeType&&s.overrideMimeType(t.mimeType),t.crossDomain||i["X-Requested-With"]||(i["X-Requested-With"]="XMLHttpRequest");for(a in i)s.setRequestHeader(a,i[a]);n=function(e){return function(){n&&(n=r=s.onload=s.onerror=s.onabort=s.ontimeout=s.onreadystatechange=null,"abort"===e?s.abort():"error"===e?"number"!=typeof s.status?o(0,"error"):o(s.status,s.statusText):o(Vt[s.status]||s.status,s.statusText,"text"!==(s.responseType||"text")||"string"!=typeof s.responseText?{binary:s.response}:{text:s.responseText},s.getAllResponseHeaders()))}},s.onload=n(),r=s.onerror=s.ontimeout=n("error"),void 0!==s.onabort?s.onabort=r:s.onreadystatechange=function(){4===s.readyState&&e.setTimeout(function(){n&&r()})},n=n("abort");try{s.send(t.hasContent&&t.data||null)}catch(e){if(n)throw e}},abort:function(){n&&n()}}}),w.ajaxPrefilter(function(e){e.crossDomain&&(e.contents.script=!1)}),w.ajaxSetup({accepts:{script:"text/javascript, application/javascript, application/ecmascript, application/x-ecmascript"},contents:{script:/\b(?:java|ecma)script\b/},converters:{"text script":function(e){return w.globalEval(e),e}}}),w.ajaxPrefilter("script",function(e){void 0===e.cache&&(e.cache=!1),e.crossDomain&&(e.type="GET")}),w.ajaxTransport("script",function(e){if(e.crossDomain){var t,n;return{send:function(i,o){t=w(" +{% endblock %} diff --git a/templates/actions.html b/templates/actions.html index 39117c6c..4d4a4eae 100644 --- a/templates/actions.html +++ b/templates/actions.html @@ -1,3 +1,12 @@ +{% block javascript %} + +{% endblock %} {% block content %}
@@ -5,36 +14,54 @@
-

Connection

- +

Diagnostics/Maintenance

+ + + Download Diagnostics File + Backup WebControl + + + +
-

Diagnostics

- - - - - - +

Calibration/Setup

+ + + + + + + + + + +
-
+
-

Calibration/Setup

- - - - - -
+

Controller

+ + + + + + + + + +
{% endblock %} + + diff --git a/templates/frontpage.html b/templates/archive/frontpage.html similarity index 71% rename from templates/frontpage.html rename to templates/archive/frontpage.html index 577789ba..96643274 100644 --- a/templates/frontpage.html +++ b/templates/archive/frontpage.html @@ -5,10 +5,11 @@ {% endblock %} {% block javascript %} + - + {% endblock %} @@ -17,44 +18,55 @@
+ +

Controls

- +
- +
- +
- +
- +
- +
- +
- +
- +
@@ -82,7 +94,7 @@

Controls

- +
@@ -103,11 +115,27 @@

Controls

-
-

Position

+
+
Sled:
+
+
+
+
+
+
+
+
Home:
+
+
+
+
+
+
+
+
Complete:
-
-

+
+
diff --git a/templates/frontpage_mobile.html b/templates/archive/frontpage_mobile.html similarity index 78% rename from templates/frontpage_mobile.html rename to templates/archive/frontpage_mobile.html index a44ac757..a1064036 100644 --- a/templates/frontpage_mobile.html +++ b/templates/archive/frontpage_mobile.html @@ -1,15 +1,16 @@ {% extends 'base.html' %} {% block header %} - + {% endblock %} {% block javascript %} + - + {% endblock %} @@ -18,24 +19,24 @@

Controls

-
-
-
-
@@ -45,24 +46,24 @@

Controls

-
-
-
-
@@ -124,14 +125,42 @@

Controls

-

Position

+
Position
-
-

+
+
+
+
+
+
+
Home:
+
+
+
+
+
+
+
+
Complete:
+
+
+
+ + +

Controller Messages

@@ -143,5 +172,6 @@

Controller Messages

+
{% endblock %} diff --git a/templates/base.html b/templates/base.html index 4bdf74c8..dd9526b4 100644 --- a/templates/base.html +++ b/templates/base.html @@ -1,127 +1,31 @@ - {% block title %}{% endblock %} - WebControl - - - - - - - + + + + + - function updateSetting(setting, value){ - socket.emit('updateSetting',{data:{setting:setting,value:value}}); - } - - function checkForGCodeUpdate(){ - socket.emit('checkForGCodeUpdate',{data:"Please"}); - } - - var isMobile = false; //initiate as false - if(/(android|bb\d+|meego).+mobile|avantgo|bada\/|blackberry|blazer|compal|elaine|fennec|hiptop|iemobile|ip(hone|od)|ipad|iris|kindle|Android|Silk|lge |maemo|midp|mmp|netfront|opera m(ob|in)i|palm( os)?|phone|p(ixi|re)\/|plucker|pocket|psp|series(4|6)0|symbian|treo|up\.(browser|link)|vodafone|wap|windows (ce|phone)|xda|xiino/i.test(navigator.userAgent) - || /1207|6310|6590|3gso|4thp|50[1-6]i|770s|802s|a wa|abac|ac(er|oo|s\-)|ai(ko|rn)|al(av|ca|co)|amoi|an(ex|ny|yw)|aptu|ar(ch|go)|as(te|us)|attw|au(di|\-m|r |s )|avan|be(ck|ll|nq)|bi(lb|rd)|bl(ac|az)|br(e|v)w|bumb|bw\-(n|u)|c55\/|capi|ccwa|cdm\-|cell|chtm|cldc|cmd\-|co(mp|nd)|craw|da(it|ll|ng)|dbte|dc\-s|devi|dica|dmob|do(c|p)o|ds(12|\-d)|el(49|ai)|em(l2|ul)|er(ic|k0)|esl8|ez([4-7]0|os|wa|ze)|fetc|fly(\-|_)|g1 u|g560|gene|gf\-5|g\-mo|go(\.w|od)|gr(ad|un)|haie|hcit|hd\-(m|p|t)|hei\-|hi(pt|ta)|hp( i|ip)|hs\-c|ht(c(\-| |_|a|g|p|s|t)|tp)|hu(aw|tc)|i\-(20|go|ma)|i230|iac( |\-|\/)|ibro|idea|ig01|ikom|im1k|inno|ipaq|iris|ja(t|v)a|jbro|jemu|jigs|kddi|keji|kgt( |\/)|klon|kpt |kwc\-|kyo(c|k)|le(no|xi)|lg( g|\/(k|l|u)|50|54|\-[a-w])|libw|lynx|m1\-w|m3ga|m50\/|ma(te|ui|xo)|mc(01|21|ca)|m\-cr|me(rc|ri)|mi(o8|oa|ts)|mmef|mo(01|02|bi|de|do|t(\-| |o|v)|zz)|mt(50|p1|v )|mwbp|mywa|n10[0-2]|n20[2-3]|n30(0|2)|n50(0|2|5)|n7(0(0|1)|10)|ne((c|m)\-|on|tf|wf|wg|wt)|nok(6|i)|nzph|o2im|op(ti|wv)|oran|owg1|p800|pan(a|d|t)|pdxg|pg(13|\-([1-8]|c))|phil|pire|pl(ay|uc)|pn\-2|po(ck|rt|se)|prox|psio|pt\-g|qa\-a|qc(07|12|21|32|60|\-[2-7]|i\-)|qtek|r380|r600|raks|rim9|ro(ve|zo)|s55\/|sa(ge|ma|mm|ms|ny|va)|sc(01|h\-|oo|p\-)|sdk\/|se(c(\-|0|1)|47|mc|nd|ri)|sgh\-|shar|sie(\-|m)|sk\-0|sl(45|id)|sm(al|ar|b3|it|t5)|so(ft|ny)|sp(01|h\-|v\-|v )|sy(01|mb)|t2(18|50)|t6(00|10|18)|ta(gt|lk)|tcl\-|tdg\-|tel(i|m)|tim\-|t\-mo|to(pl|sh)|ts(70|m\-|m3|m5)|tx\-9|up(\.b|g1|si)|utst|v400|v750|veri|vi(rg|te)|vk(40|5[0-3]|\-v)|vm40|voda|vulc|vx(52|53|60|61|70|80|81|83|85|98)|w3c(\-| )|webc|whit|wi(g |nc|nw)|wmlb|wonu|x700|yas\-|your|zeto|zte\-/i.test(navigator.userAgent.substr(0,4))) { - isMobile = true; - } + -
+
@@ -165,7 +110,7 @@
+{% endblock %} diff --git a/templates/frontpageText.html b/templates/frontpageText.html new file mode 100644 index 00000000..69fce26c --- /dev/null +++ b/templates/frontpageText.html @@ -0,0 +1,230 @@ +{% extends 'base.html' %} + +{% block header %} + + +{% endblock %} + +{% block javascript %} + + + + +{% endblock %} + +{% block content %} +
+

Controls

+
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+
+
+
No alerts
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+ +
+
+
Line #:
+
+
+ +
+
+ +
+
+
+
+
Line:
+
+
+
+
+
+
+
+
Position
+
+
+
+
+
+
+
+
Error:
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
Home:
+
+
+
+
+
+
+
+
Complete:
+
+
+
+
+
+
State:
+
+
+
+
+
+
+
+
Tool:
+
+
+
+
+
+
Positioning:
+
+
+
+
+
+ +
+
+

Controller Messages

+
+
+
+
+
+
+
+
+
+{% endblock %} diff --git a/templates/gettingStarted.html b/templates/gettingStarted.html new file mode 100644 index 00000000..bbbaf9b5 --- /dev/null +++ b/templates/gettingStarted.html @@ -0,0 +1,59 @@ + +{% block content %} +
+
+
+

If you are coming from using GroundControl:

+

My recommendation is to import your groundcontrol.ini file before proceeding any further.

+

Go to Actions->Import groundcontrol.ini

+

If all goes well and the comport assignment is still the same, you should be able to communicate with the controller.

+

If you are starting anew:

+

1) Set ComPort

+

Go to Settings->Maslow Settings->COMPort and select the comport for the arduino controller.  Press the 'refresh' symbol to populate the list of available comports (give it a couple of seconds if you have a bluetooth enabled on the computer running webcontrol).  Don't forget to press submit.  If all goes well, you should see messages coming from the controller in the lower right portion of the screen (Controller Messages)

+
+ +
COMPort Setting
+
+

2) Set Distance to Extend Chains

+

If you are using a top beam that's longer than 10 feet, go to Settings->Advanced Settings->Extend Chain Distance.  If using a 12-foot beam, change to 2032.  This is the amount of chain that will be extended to allow you to connect up the sled.  Too little and they won't meet and too much, the sled may be on the floor.  You don't have to use a value that perfectly equates to the center of the board, just make sure it's a multiple of 6.35 mm.

+
+ +
Extend Chain Distance
+
+

3) Quick Configure

+

Go to Actions->Quick Configure and enter the requested information.  This lets the controller know enough about the setup to allow you to calibrate the machine.  Don't forget to press submit.

+

4) Set Sprockets Vertical

+

Go to Actions->Set Sprockets Vertical:

+

4a) Get one tooth of each sprocket as precisely vertical as you can using the buttons.  When done, press 'Define Zero'.  This tells the controllers that the chain length is 0. 

+
+ +
Sprocket with Vertical Tooth
+
+

4b) Install the chains on the sprocket such that the first link is resting on the top sprocket tooth. The placement depends on if you built the frame for "Chains Off Top" or "Chains Off Bottom" 

+
+ +
Chains Off Bottom
+
+
+ +
Chains Off Top
+
+

4c) Extend left chain. Press 'Extend Left Chain to xxxx mm' where xxxx is the distance set in Step 2.  Warning: This is one spot where the chains can get wrapped around the sprocket.  Grab hold of the end of the chain and apply tension to it as it feeds off the sprocket so it doesn't wrap.

+

4d) Extend right chain. Press 'Extend Right Chain to xxxx mm' where xxxx is the distance set in Step 2.  Warning: Same as above.

+

4e) Connect Sled.  Connect up your sled to the extended chains.

+

4f) Mark chains.  Take a marker, nail polish, something, and mark the specific chain link that is on top of the top tooth.  If the 'Extend Chain Distance' is a multiple of 6.35 mm, there should be a tooth perfectly vertical after extending the chains.  Mark this because if you ever have to reset the chains, you need to know which link is this one.

+

5) Calibrate

+

5a) If using stock firwmare, go to 'Actions->Triangular Calibration.'  If using holey calibration firmware, go to 'Actions->Holey Calibration'

+

5a) Press 'Cut Calibration Pattern' and wait for the sled to complete the cutting.

+

5b) Enter measurements as requested.

+

5c) Press 'Calculate'

+

5d) If all looks good, press 'Accept Results' (you may have to scroll down the screen to see it)

+

5e) Dance a jig.  You're calibrated.

+
+
+
+{% endblock %} + +{% block javascript %} + +{% endblock %} diff --git a/templates/gpio.html b/templates/gpio.html new file mode 100644 index 00000000..2c58f3a6 --- /dev/null +++ b/templates/gpio.html @@ -0,0 +1,38 @@ +{% block content %} +
+ +
+
+
+ {% for setting in settings %} +
+
+ {{setting.title}}

+
+
+ {% if setting.type=="options" %} + + {% endif %} +
+
+ {% endfor %} +
+
+ +
+
+ +
+
+{% endblock %} + +{% block javascript %} + + +{% endblock %} \ No newline at end of file diff --git a/templates/gpio_mobile.html b/templates/gpio_mobile.html new file mode 100644 index 00000000..f566d771 --- /dev/null +++ b/templates/gpio_mobile.html @@ -0,0 +1,35 @@ +{% block content %} +
+ +
+
+
+ {% for setting in settings %} +
+
+ {{setting.title}}

+
+
+ {% if setting.type=="options" %} + + {% endif %} +
+
+ {% endfor %} +
+
+ +
+
+{% endblock %} + +{% block javascript %} + + +{% endblock %} \ No newline at end of file diff --git a/templates/help.html b/templates/help.html new file mode 100644 index 00000000..5460fa72 --- /dev/null +++ b/templates/help.html @@ -0,0 +1,13 @@ +{% block content %} +
+ +
+
+ {{helpIndex|safe}} +
+
+ {{helpPage|safe}} +
+
+
+{% endblock %} diff --git a/templates/helpPages.html b/templates/helpPages.html new file mode 100644 index 00000000..414ccb87 --- /dev/null +++ b/templates/helpPages.html @@ -0,0 +1,16 @@ +{% block content %} +
+ +
    + {% for page in helpPages %} +
  • + {{page.name}} +
  • + {% endfor %} +
+
+{% endblock %} + +{% block javascript %} + +{% endblock %} \ No newline at end of file diff --git a/templates/help_mobile.html b/templates/help_mobile.html new file mode 100644 index 00000000..c7beb770 --- /dev/null +++ b/templates/help_mobile.html @@ -0,0 +1,7 @@ +{% block content %} +
+ + {{helpIndex|safe}} + {{helpPage|safe}} +
+{% endblock %} diff --git a/templates/holeyCalibration.html b/templates/holeyCalibration.html new file mode 100644 index 00000000..2a011918 --- /dev/null +++ b/templates/holeyCalibration.html @@ -0,0 +1,133 @@ + +{% block content %} +
+
+

Cut Test Pattern

+ + +
+
+

Measurements

+
+ + +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+ + + Enter value in mm only +
+
+
+ +
+
+ +
+
+
+
+
+
+

Results

+

+

+

+

+

+
+
+{% endblock %} + +{% block javascript %} + +{% endblock %} diff --git a/templates/importFile.html b/templates/importFile.html index fa195d77..fd0a6114 100644 --- a/templates/importFile.html +++ b/templates/importFile.html @@ -1,3 +1,4 @@ + {% block content %}
@@ -19,7 +20,7 @@ var formdata = new FormData(this); $.ajax({ - url : '/importFile', + url : '/{{url}}', type: "POST", data: formdata, mimeTypes:"multipart/form-data", @@ -28,7 +29,7 @@ processData: false, success: function (data) { console.log("success"); - $('#notificationModal').modal('toggle') + $('#contentModal').modal('toggle') }, error: function (jXHR, textStatus, errorThrown) { alert(errorThrown); diff --git a/templates/logs.html b/templates/logs.html new file mode 100644 index 00000000..bdf441d4 --- /dev/null +++ b/templates/logs.html @@ -0,0 +1,55 @@ + + + {% block title %}{% endblock %}WebControl Logs + + + + + + + + + + + + + +
+
+
Waiting for Status...
+
+
+
+
+
+

Log

+
+
+ + + + +
+
+
+
+
+
+
+

Abridged Log

+
+
+ + + + +
+
+
+
+
+
+ + +{% block javascript %}{% endblock %} diff --git a/templates/openBoard.html b/templates/openBoard.html new file mode 100644 index 00000000..36771218 --- /dev/null +++ b/templates/openBoard.html @@ -0,0 +1,42 @@ +{% block content %} +
+ +
+
+ + +
+
+ + +
+
+ +
+
+
+
+
+
+
+
+ + +
+{% endblock %} + +{% block javascript %} + +{% endblock %} diff --git a/templates/openGCode.html b/templates/openGCode.html index 7ebc1f0c..43e67c83 100644 --- a/templates/openGCode.html +++ b/templates/openGCode.html @@ -1,46 +1,42 @@ {% block content %}
-
-
- + +
+
+ + +
+
+ + +
- + +
+
+
+
+
+
+
+
+
{% endblock %} {% block javascript %} - + {% endblock %} diff --git a/templates/opticalCalibration.html b/templates/opticalCalibration.html index a6c94e6b..5874b48c 100644 --- a/templates/opticalCalibration.html +++ b/templates/opticalCalibration.html @@ -1,231 +1,473 @@ {% block content %}
-
- -
-
-
-
-
- - - Enter value in inches only +
+ {% if isMobile == true %} +
+
+ +
+
+
+
+
+ + + Enter value in inches only +
+
+
+
+ + + Enter value in inches only +
+
-
-
-
- - - Enter value in inches only +
+
+
+ + + Enter something like 1.0028 +
+
+
+
+ + + Enter something like 1.0028 +
+
+
+
+
+
+ + + Enter something like 300 +
+
+
+
+ + + Enter something like 200 +
+
+
+
+
+
+ + + Enter something like 0.125 (mm) +
+
+
-
-
-
- - - Enter something like 1.0028 +
+
+
+
+ +
+
+

Calibration Extents

+ +
+
+
+ + + Range from +15 to -15 (+ is right, - is left) +
-
-
-
- - - Enter something like 1.0028 +
+
+ + + Range from +7 to -7 (+ is up, - is down) +
+
+
+
+
+
+ + + Range from +15 to -15 (+ is right, - is left) +
+
+
+
+ + + Range from +7 to -7 (+ is up, - is down) +
+
+
+
+
+ + +
+
+
+
-
-
-
- - - Enter something like 300 +
+
+ {% else %} +
+
+ +
+
+
+
+
+

Configuration

+
+
+
+ + + Enter value in inches only +
+
+
+
+ + + Enter value in inches only +
+
+
+
+
+
+ + + Enter something like 1.0028 +
+
+
+
+ + + Enter something like 1.0028 +
+
+
+
+
+
+ + + Enter something like 300 +
+
+
+
+ + + Enter something like 200 +
+
+
+
+
+
+ + + Enter something like 0.125 (mm) +
+
+
+
+
-
-
-
- - - Enter something like 200 +
+
+
+

Calibration Extents

+ +
+
+
+ + + Range from +15 to -15 (+ is right, - is left) +
+
+
+
+ + + Range from +7 to -7 (+ is up, - is down) +
+
+
+
+
+
+ + + Range from +15 to -15 (+ is right, - is left) +
+
+
+
+ + + Range from +7 to -7 (+ is up, - is down) +
+
+
+
+
+
+ + +
+
+
+
+
-
+
+
+ {% endif %}
-
- -
+
-

Calibration Extents

-
-
-
- - - Enter something like -15 +
+
+
+
+
+ + + 0-255 +
+
+
+
+ + + 0-255 +
+
+
+
+
+ + +
+
+ +
+
+ +
+
+ +
+
+
+
+
+
+ +
+
+ +
+ +
+
-
-
-
- - - Enter something like 7 +
+
+
+
+
+
+
+
-
-
-
-
- - - Enter something like 15 + +
+
+
+
+ +
+
+ + +
+ {% if isMobile==false %} +
+
+
+
+
+
+ {% else %} +
+
+ {% endif %}
+
-
-
- - - Enter something like -7 +
+
+
+ +
+
+ +
+ {% if isMobile==false %} +
+
+
+
+
+
+ {% else %} +
+
+ {% endif %} +
+
-
-

Calibration

- +
- +
- +
- +
+
+
+ +
+
+
+
+ +
+
+ +
+ +
-
-
-

Active Image

-
+
+
+
+
+

Active Image

+
+
+
-
-
-
-

Sled Position

-
+
+
+
+

Sled Position

+
+
+
-
- +
+ {% endblock %} {% block javascript %} - - - + + + + + {% endblock %} diff --git a/templates/pidTuning.html b/templates/pidTuning.html new file mode 100644 index 00000000..3b50622c --- /dev/null +++ b/templates/pidTuning.html @@ -0,0 +1,477 @@ + +{% block content %} +
+
+ +
+
+
+
+
+

Top Left Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+
+
+
+
+

Top Right Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+
+
+ {% if fourMotor == true %} +
+
+
+
+

Bottom Left Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+
+
+
+
+

Bottom Right Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+
+
+ {% endif %} +
+
+
+ +
+
+
+
+

Settings

+
+
+
+ +
+ + + {% if fourMotor == true %} + + + {% endif %} +
+
+
+
+
+
+
+ + + +
+
+
+
+ + + +
+
+
+
+
+
+ + + +
+
+
+
+ + + +
+
+
+
+
+
+ + + +
+
+
+
+ + + +
+
+
+
+ + + +
+
+
+ +
+
+
+
+

Test Results

+
+
+
+
+
+
+
+
+
+ +
+
+
+
+

Settings

+
+
+
+ +
+ + + {% if fourMotor == true %} + + + {% endif %} +
+
+
+
+
+
+
+ + + +
+
+
+
+ + + +
+
+
+
+
+
+ + + +
+
+
+
+ + + +
+
+
+
+
+
+ + + +
+
+
+
+
+
+ + + +
+
+
+
+ + + +
+
+
+
+ + + +
+
+
+ +
+
+
+
+

Test Results

+
+
+
+
+
+
+
+
+
+{% endblock %} + +{% block javascript %} + + + +{% endblock %} diff --git a/templates/quickConfigure.html b/templates/quickConfigure.html index fde5d28b..278a4e72 100644 --- a/templates/quickConfigure.html +++ b/templates/quickConfigure.html @@ -8,25 +8,47 @@

Kinematics Kit

Select your type of kit or provide a custom value for rotational radius. Note: Quadrilateral kits have no rotational radius, you can leave it zero. If you've come back to this page and see your setting is custom, don't worry. Custom means a triangular kit. As long as its marked custom and has a rotational radius entered, you're good to go (unless of course you are using a quadrilateral kit for some reason)

-
Ring
- -
Linkage
- -
Pantograph
- -
Quadrilateral
- +
+
+
Ring
+ +
+
+
Linkage
+ +
+
+
+
+
Pantograph
+ +
+
+
Quadrilateral
+ +
+
+
+
+
Metal Maslow Linkage
+ +
+
+
+
+

- + Enter value in mm only
@@ -53,12 +75,12 @@

Distance Between Motors

to sprocket center. There's a handy button you can press to make that subtraction for you if you like. Your choice.

Measure sprocket to sprocket:

- +

Or measure gearbox to gearbox (and don't forget to subtract 40.4 mm!):

- +

- + Enter value in mm only
@@ -73,7 +95,7 @@

Height of Motors Above Workspace

- + Enter value in mm only
@@ -97,7 +119,7 @@

Height of Motors Above Workspace

data: $(this).serialize(), success: function (data) { console.log("success"); - $('#notificationModal').modal('toggle') + $('#contentModal').modal('toggle') }, error: function (jXHR, textStatus, errorThrown) { alert(errorThrown); @@ -117,6 +139,9 @@

Height of Motors Above Workspace

case "Pantograph": rotationRadius = 100; break; + case "Metal Maslow": + rotationRadius = 180.34; + break; case "Quadrilateral": rotationRadius = 0; break; diff --git a/templates/releases.html b/templates/releases.html new file mode 100644 index 00000000..c05f7147 --- /dev/null +++ b/templates/releases.html @@ -0,0 +1,33 @@ +{% block content %} +
+ +
    + {% for release in releases %} +
  • +
    +
    +

    {{release.tag_name}}

    +
    +
    +

    {{release.title}}

    +

    {{release.body|markdown}}

    +
    +
    + {% if release.tag_name == currentRelease %} + + {% elif release.tag_name == latestRelease.tag_name %} + + {% else %} + + {% endif %} +
    +
    +
  • + {% endfor %} +
+
+{% endblock %} + +{% block javascript %} + +{% endblock %} \ No newline at end of file diff --git a/templates/releases_mobile.html b/templates/releases_mobile.html new file mode 100644 index 00000000..0ed4f59a --- /dev/null +++ b/templates/releases_mobile.html @@ -0,0 +1,31 @@ +{% block content %} +
+ +
    + {% for release in releases %} +
  • +
    +

    {{release.tag_name}}

    +
    +
    +

    {{release.title}}

    +

    {{release.body|markdown}}

    +
    +
    + {% if release.tag_name == currentRelease %} + + {% elif release.tag_name == latestRelease.tag_name %} + + {% else %} + + {% endif %} +
    +
  • + {% endfor %} +
+
+{% endblock %} + +{% block javascript %} + +{% endblock %} \ No newline at end of file diff --git a/templates/resetChains.html b/templates/resetChains.html new file mode 100644 index 00000000..3079bbeb --- /dev/null +++ b/templates/resetChains.html @@ -0,0 +1,243 @@ + +{% block content %} +
+

Left Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+

Right Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+ + {% if fourMotor == true %} +

Bottom Left Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+

Bottom Right Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+ {% endif %} + + + + + +
+
+ +
+
+ +
+
+ +
+
+
+ +{% endblock %} + +{% block javascript %} + + + +{% endblock %} diff --git a/templates/resetChains_mobile.html b/templates/resetChains_mobile.html new file mode 100644 index 00000000..067dbb12 --- /dev/null +++ b/templates/resetChains_mobile.html @@ -0,0 +1,129 @@ + +{% block content %} +
+

Left Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+

Right Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+
+ +{% endblock %} + +{% block javascript %} + + + +{% endblock %} diff --git a/templates/saveBoard.html b/templates/saveBoard.html new file mode 100644 index 00000000..d3af41e1 --- /dev/null +++ b/templates/saveBoard.html @@ -0,0 +1,50 @@ +{% block content %} +
+
+ +
+
+ + +
+
+ + +
+
+
+ + +
+
+ +
+ +
+
+
+
+
+
+
+
+ + +
+{% endblock %} + +{% block javascript %} + +{% endblock %} diff --git a/templates/saveGCode.html b/templates/saveGCode.html new file mode 100644 index 00000000..4c7e8183 --- /dev/null +++ b/templates/saveGCode.html @@ -0,0 +1,50 @@ +{% block content %} +
+
+ +
+
+ + +
+
+ + +
+
+
+ + +
+
+ +
+ +
+
+
+
+
+
+
+
+ + +
+{% endblock %} + +{% block javascript %} + +{% endblock %} diff --git a/templates/screenAction.html b/templates/screenAction.html new file mode 100644 index 00000000..e900a6fa --- /dev/null +++ b/templates/screenAction.html @@ -0,0 +1,30 @@ + +{% block content %} +
+
+
+ +
+
+ +
+
+
+
+ +
+
+
+ +{% endblock %} + +{% block javascript %} + + +{% endblock %} diff --git a/templates/sendGCode.html b/templates/sendGCode.html new file mode 100644 index 00000000..d7791db4 --- /dev/null +++ b/templates/sendGCode.html @@ -0,0 +1,41 @@ +{% block content %} + +
+
{{gcode}}
+  
+
+{% endblock %} + +{% block javascript %} + + + + + +{% endblock %} + + + diff --git a/templates/setSprockets.html b/templates/setSprockets.html index 7085a327..b149e7af 100644 --- a/templates/setSprockets.html +++ b/templates/setSprockets.html @@ -3,52 +3,52 @@

Left Motor

-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- @@ -56,65 +56,187 @@

Left Motor

Right Motor

-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+ + {% if fourMotor == true %} +

Bottom Left Motor

-
- +
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+

Bottom Right Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+ {% endif %} + + + + + +
+
+ +
+
+
+
+ +
+
+ +
+
+
- +
@@ -122,7 +244,7 @@

Right Motor

{% endblock %} {% block javascript %} - + {% endblock %} diff --git a/templates/setSprockets_mobile.html b/templates/setSprockets_mobile.html new file mode 100644 index 00000000..4a0f99a5 --- /dev/null +++ b/templates/setSprockets_mobile.html @@ -0,0 +1,136 @@ + +{% block content %} +
+

Left Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+

Right Motor

+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+ +
+
+ +
+
+ +
+
+
+
+ +
+
+
+
+ +
+
+ +
+
+
+
+ +
+
+
+ +{% endblock %} + +{% block javascript %} + + + +{% endblock %} diff --git a/templates/settings.html b/templates/settings.html index e2eb1be5..94cd7639 100644 --- a/templates/settings.html +++ b/templates/settings.html @@ -7,8 +7,8 @@
  • -

    {{setting.title}}

    -

    {{setting.desc}}

    +

    {{setting.title}}

    +

    {{setting.desc}}

    {% if setting.key =="COMport" %} @@ -33,7 +33,7 @@

    {{setting.title}}

    {% elif setting.type=="options" %} - {% for option in setting.options %}
  • {% endfor %} - +
    {% endblock %} {% block javascript %} - + -{% endblock %} +{% endblock %} \ No newline at end of file diff --git a/templates/settings_mobile.html b/templates/settings_mobile.html index dabbe4f7..a10e22a2 100644 --- a/templates/settings_mobile.html +++ b/templates/settings_mobile.html @@ -6,29 +6,34 @@ {% for setting in settings %}
  • -
    -

    {{setting.title}}

    -

    {{setting.desc}}

    +
    +

    {{setting.title}}

    +

    {{setting.desc}}

    -
    -
    -
    +
    {% if setting.key =="COMport" %} - + {% if ports|length == 0 %} + - {% endfor %} - {% endif %} - + {% else %} + {% for port in ports %} + + {% endfor %} + {% endif %} + +
    + +
    +
    {% elif setting.type=="options" %} - {% for option in setting.options %}
    - +
  • {% endfor %} - +
    {% endblock %} {% block javascript %} - + + {% endblock %} diff --git a/templates/triangularCalibration..html b/templates/triangularCalibration..html deleted file mode 100644 index 7d880cb2..00000000 --- a/templates/triangularCalibration..html +++ /dev/null @@ -1,72 +0,0 @@ - -{% block content %} -
    -
    Cut Test Pattern
    - - -
    Measurements
    -
    -
    -
    - -
    -
    - - - Enter value in mm only -
    -
    - - - Enter value in mm only -
    -
    - - - Enter value in mm only -
    -
    - - - Enter value in mm only -
    - -
    -
    -
    -
    -
    Parameters
    -

    -

    -

    -

    - -
    -{% endblock %} - -{% block javascript %} - -{% endblock %} diff --git a/templates/triangularCalibration.html b/templates/triangularCalibration.html new file mode 100644 index 00000000..1a3a0f49 --- /dev/null +++ b/templates/triangularCalibration.html @@ -0,0 +1,83 @@ + +{% block content %} +
    +
    Cut Test Pattern
    + + +
    Measurements
    +
    + + +
    +
    + + + Enter value in mm only +
    +
    + + + Enter value in mm only +
    +
    + + + Enter value in mm only +
    +
    + + + Enter value in mm only +
    +
    +
    + +
    +
    + +
    +
    +
    +
    +
    Parameters
    +

    +

    +

    +

    +
    +{% endblock %} + +{% block javascript %} + +{% endblock %} diff --git a/templates/trimBoard.html b/templates/trimBoard.html new file mode 100644 index 00000000..ac8257ad --- /dev/null +++ b/templates/trimBoard.html @@ -0,0 +1,58 @@ + +{% block content %} +
    +
    + + +
    +
    + + + Enter value in {{units}} only +
    +
    +
    +
    + + + Enter value in {{units}} only +
    +
    + + + Enter value in {{units}} only +
    +
    +
    +
    + + + Enter value in {{units}} only +
    +
    +
    +
    +{% endblock %} + +{% block javascript %} + +{% endblock %} + + diff --git a/templates/uploadGCode.html b/templates/uploadGCode.html index f90520b1..1dce642e 100644 --- a/templates/uploadGCode.html +++ b/templates/uploadGCode.html @@ -2,40 +2,37 @@
    - - +
    + + + + +
    +
    + Select File to Upload +
    +
    + +
    + + +
    + +
    - +
    {% endblock %} {% block javascript %} - - $.ajax({ - url : '/uploadGCode', - type: "POST", - data: formdata, - mimeTypes:"multipart/form-data", - contentType: false, - cache: false, - processData: false, - success: function (data) { - console.log("success"); - $('#notificationModal').modal('toggle') - checkForGCodeUpdate(); - }, - error: function (jXHR, textStatus, errorThrown) { - alert(errorThrown); - } - }); - }); -}); - {% endblock %} diff --git a/templates/zaxis.html b/templates/zaxis.html index cd6d7944..024e8c45 100644 --- a/templates/zaxis.html +++ b/templates/zaxis.html @@ -5,34 +5,36 @@
    - +
    - +
    - +
    - +
    - +
    - +
    - +
    {% endblock %} {% block javascript %} - + + + {% endblock %} diff --git a/templates/zaxis_mobile.html b/templates/zaxis_mobile.html new file mode 100644 index 00000000..a22c2179 --- /dev/null +++ b/templates/zaxis_mobile.html @@ -0,0 +1,42 @@ + +{% block content %} +
    +
    +
    +
    +
    + +
    +
    + +
    +
    +
    +
    + +
    +
    + +
    +
    +
    +
    + +
    +
    + +
    +
    +
    + +
    +
    +
    +
    +{% endblock %} + +{% block javascript %} + + + +{% endblock %} diff --git a/tools/download_build_install_opencv.sh b/tools/download_build_install_opencv.sh index 40033ed7..0e760343 100644 --- a/tools/download_build_install_opencv.sh +++ b/tools/download_build_install_opencv.sh @@ -12,6 +12,7 @@ wget -O opencv.zip https://github.com/opencv/opencv/archive/$OPENCV_VERSION.zip unzip opencv.zip rm -rf opencv.zip +# TODO: Try with no opencv_contrib (we might not need it for optical calibration) wget -O opencv_contrib.zip https://github.com/opencv/opencv_contrib/archive/$OPENCV_VERSION.zip unzip opencv_contrib.zip rm -rf opencv_contrib.zip @@ -26,9 +27,15 @@ cmake -D CMAKE_BUILD_TYPE=RELEASE \ -D CMAKE_INSTALL_PREFIX=/usr/local \ -D OPENCV_EXTRA_MODULES_PATH=$OPENCV_CONTRIB_MODULES_SRC_DIR \ -D BUILD_SHARED_LIBS=OFF \ + -D ENABLE_NEON=ON \ + -D ENABLE_VFPV3=ON \ + -D BUILD_TESTS=OFF \ + -D INSTALL_PYTHON_EXAMPLES=OFF \ + -D BUILD_EXAMPLES=OFF \ + -D BUILD_PERF_TESTS=OFF \ .. -make -j4 +make -j$(python3 -c 'import multiprocessing as mp; print(int(mp.cpu_count() * 1.5))') make install ldconfig diff --git a/tools/repair_webcontrol.sh b/tools/repair_webcontrol.sh new file mode 100644 index 00000000..e69de29b diff --git a/tools/upgrade_webcontrol.sh b/tools/upgrade_webcontrol.sh new file mode 100644 index 00000000..8ec7c7bf --- /dev/null +++ b/tools/upgrade_webcontrol.sh @@ -0,0 +1,7 @@ +#!/bin/bash +sleep 3 +echo $1 +echo $2 +cd $2 +tar -zxvf $1 +./webcontrol diff --git a/tools/upgrade_webcontrol_win.bat b/tools/upgrade_webcontrol_win.bat new file mode 100644 index 00000000..7a886cab --- /dev/null +++ b/tools/upgrade_webcontrol_win.bat @@ -0,0 +1,7 @@ +PING localhost -n 4 >NUL +echo %1 +echo %2 +echo %3 +cd %2 +%3 x -y %1 +start "" "webcontrol" diff --git a/uselib.py b/uselib.py new file mode 100644 index 00000000..5c596dba --- /dev/null +++ b/uselib.py @@ -0,0 +1,3 @@ +import sys +import os +sys.path.append(os.path.join(os.path.dirname(sys.argv[0]), "lib")) \ No newline at end of file diff --git a/webcontrol-us-recipe.xml b/webcontrol-us-recipe.xml new file mode 100644 index 00000000..dc525599 --- /dev/null +++ b/webcontrol-us-recipe.xml @@ -0,0 +1 @@ +ex -s -c '49i|os.system("wpa_cli -i wlan0 reconfigure")' -c x /boot/PiBakery/blocks/wifisetup/wifiConnect.pyroot<your network><your password>WPA/WPA2USex -s -c '27i|curl -A "PiBakery" -k -o "$2" "$1" -L' -c x /boot/PiBakery/blocks/downloadfile/downloadFile.shrootex -s -c '25i|curl -A "PiBakery" -k -o "$2/$filename" "$1" -L' -c x /boot/PiBakery/blocks/downloadfile/downloadFile.shrootwebcontrolmkdir /home/pi/webcontrolpicd /home/pi/webcontrolpihttps://github.com/madgrizzle/WebControl/releases/download/v0.922/webcontrol-0.922-rpi-singledirectory.tar.gz/home/pi/webcontrol/webcontrol-0.922-rpi-singledirectory.tar.gztar -C /home/pi/webcontrol -zxvf /home/pi/webcontrol/webcontrol-0.922-rpi-singledirectory.tar.gzpisudo raspi-config nonint do_change_locale "en-US.UTF-8"rootsudo raspi-config nonint do_configure_keyboard "us"root/home/pi/webcontrol/webcontrol&pi \ No newline at end of file diff --git a/webcontrolicon_256px.ico b/webcontrolicon_256px.ico new file mode 100644 index 00000000..3a128307 Binary files /dev/null and b/webcontrolicon_256px.ico differ diff --git a/wiicontrol.code-workspace b/wiicontrol.code-workspace new file mode 100644 index 00000000..362d7c25 --- /dev/null +++ b/wiicontrol.code-workspace @@ -0,0 +1,7 @@ +{ + "folders": [ + { + "path": "." + } + ] +} \ No newline at end of file