#------IMPORTS-------
from pygestalt import nodes
from pygestalt import interfaces
from pygestalt import machines
from pygestalt import functions
from pygestalt.machines import elements
from pygestalt.machines import kinematics
from pygestalt.machines import state
from pygestalt.utilities import notice
from pygestalt.publish import rpc	#remote procedure call dispatcher
import time
import io
import random
import sys
import os
import time
from Tkinter import *

#------VIRTUAL MACHINE------
class virtualMachine(machines.virtualMachine):
    
    def initInterfaces(self):
        if self.providedInterface: self.fabnet = self.providedInterface		#providedInterface is defined in the virtualMachine class.
        else: self.fabnet = interfaces.gestaltInterface('FABNET', interfaces.serialInterface(baudRate = 115200, interfaceType = 'ftdi', portName = '/dev/tty.usbserial-FTXW4F9H'))
        
    def initControllers(self):
        self.xAxisNode = nodes.networkedGestaltNode('X Axis', self.fabnet, filename = '086-005a.py', persistence = self.persistence)
        self.yAxisNode = nodes.networkedGestaltNode('Y Axis', self.fabnet, filename = '086-005a.py', persistence = self.persistence)
        self.uAxisNode = nodes.networkedGestaltNode('U Axis', self.fabnet, filename = '086-005a.py', persistence = self.persistence)
                
        self.xyuNode = nodes.compoundNode(self.xAxisNode, self.yAxisNode, self.uAxisNode)

    def initCoordinates(self):
        self.position = state.coordinate(['mm','mm','mm'])
        
    def initKinematics(self):
        self.xAxis = elements.elementChain.forward([elements.microstep.forward(4), elements.stepper.forward(1.8), elements.leadscrew.forward(8), elements.invert.forward(False)])
        self.yAxis = elements.elementChain.forward([elements.microstep.forward(4), elements.stepper.forward(1.8), elements.leadscrew.forward(8), elements.invert.forward(False)])
        self.uAxis = elements.elementChain.forward([elements.microstep.forward(4), elements.stepper.forward(1.8), elements.leadscrew.forward(8), elements.invert.forward(False)])

        self.stageKinematics = kinematics.direct(3)	#direct drive on all axes
        
    def initFunctions(self):
        self.move = functions.move(virtualMachine = self, virtualNode = self.xyuNode, axes = [self.xAxis, self.yAxis, self.uAxis], kinematics = self.stageKinematics, machinePosition = self.position,planner = 'null')
        self.jog = functions.jog(self.move)	#an incremental wrapper for the move function
        pass
        
    def initLast(self):
#       self.machineControl.setMotorCurrents(aCurrent = 0.8, bCurrent = 0.8, cCurrent = 0.8)
#       self.xyzNode.setVelocityRequest(0)	#clear velocity on nodes. Eventually this will be put in the motion planner on initialization to match state.
        pass
        
    def publish(self):
#       self.publisher.addNodes(self.machineControl)
        pass
        
    def getPosition(self):
        return {'position':self.position.future()}
        
    def setPosition(self, position  = [None, None, None]):
        self.position.future.set(position)
        
    def setSpindleSpeed(self, speedFraction):
#       self.machineControl.pwmRequest(speedFraction)
        pass

#------IF RUN DIRECTLY FROM TERMINAL------
if __name__ == '__main__':
    # The persistence file remembers the node you set. It'll generate the first time you run the
    # file. If you are hooking up a new node, delete the previous persistence file.
    stages = virtualMachine(persistenceFile = "test.vmp")
        
    # You can load a new program onto the nodes if you are so inclined. This is currently set to
    # the path to the 086-005 repository on Nadya's machine.
    #stages.xyNode.loadProgram('../../../086-005/086-005a.hex')
        
    # This is a widget for setting the potentiometer to set the motor current limit on the nodes.
    # The A4982 has max 2A of current, running the widget will interactively help you set.
    #stages.xyNode.setMotorCurrent(0.7)
        
    # This is for how fast... the stages move (?)
    stages.xyuNode.setVelocityRequest(8)

    # Base values used for while-loop
    operation = [0,0,0]
    manual = [operation]

    #From the physical absolute-zero; this is the most balanced point
    #abs_zero = [10,5,0]

    #Go an return to the first answer; "Use antimony"
    #neg_one uses the last value from 'ans_one' as zero... this should be corrected
    ans_one = [[0,25,0],[100,125,100] ] #use antimony
    neg_one = [[25,52.5,12.5],[0,0,0]]

    ans_two = [[0,60,0],[80,140,80],[80,135,70]] #ask niel
    neg_two = [[-60,-60,-60],[-75,-135,-75]]

    ans_thr = [[45,0,40],[45,0,60],[60,0,60],[125,65,125]]#japanese
    neg_thr = [[-60,-60,-60],[-130,-65,-125]]

    var = 1

    while var == 1:
    
        inn = raw_input(">> ")
        ans_list = [ans_one, ans_two, ans_thr]
        rnd_ans = random.choice(ans_list)
        
        # Single direction control
        if inn == "q":
            operation[0] = operation[0] + 5
            print "Coordiantes: ", operation[0:4]
        elif inn == "w":
            operation[1] = operation[1] + 5
            print "Coordiantes: ", operation[0:4]
        elif inn == "e":
            operation[2] = operation[2] + 5
            print "Coordiantes: ", operation[0:4]

    # Negative single direction control
        elif inn == "Q":
            operation[0] = operation[0] - 5
            print "Coordiantes: ", operation[0:4]
        elif inn == "W":
            operation[1] = operation[1] - 5
            print "Coordiantes: ", operation[0:4]
        elif inn == "E":
            operation[2] = operation[2] - 5
            print "Coordiantes: ", operation[0:4]

    # Positive & negative +- 5 control
        elif inn == "z":
            operation[0] = operation[0] + 5
            operation[1] = operation[1] + 5
            operation[2] = operation[2] + 5
            print "Coordiantes: ", operation[0:4]

        elif inn == "x":
            operation[0] = operation[0] - 5
            operation[1] = operation[1] - 5
            operation[2] = operation[2] - 5
            print "Coordiantes: ", operation[0:4]
       
        elif inn == "Z":
            operation[0] = operation[0] + 50
            operation[1] = operation[1] + 50
            operation[2] = operation[2] + 50
            print "Coordiantes: ", operation[0:4]
        
        elif inn == "X":
            operation[0] = operation[0] - 50
            operation[1] = operation[1] - 50
            operation[2] = operation[2] - 50
            print "Coordiantes: ", operation[0:4]

        elif inn == "c":
            break

    # Random answer selector
        elif inn == "r":
            manual = rnd_ans
            print "Coordiantes: ", manual

    # Answer selection
        elif inn == "1": # 1
            manual = ans_one
            print "Coordinates: ", manual
        elif inn  == "-1":
            manual = neg_one
            print "Coordinates: ", manual
        elif inn == "2": # 2
            manual = ans_two
            print "Coordinates: ", manual
        elif inn ==  "-2":
            manual = neg_two
            print "Coordinates: ", manual
        elif inn == "3": # 3
            manual = ans_thr
            print "Coordinates: ", manual
        elif inn == "-3":
            manual = neg_thr
            print "Coordinates: ", manual
        else:
            operation = operation
            var = 2

        for move in manual:
            stages.move(move, 0)
            status = stages.xAxisNode.spinStatusRequest()
        # This checks to see if the move is done.
            while status['stepsRemaining'] > 0:
                time.sleep(0.001)
                status = stages.xAxisNode.spinStatusRequest()
