# Two stage example Virtual Machine file
# moves get set in Main
# usb port needs to be set in initInterfaces
# Nadya Peek Dec 2014

#------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 math
import serial
import random
import datetime
import telepot
import Queue

def bot_parse_command(cmd):
	if len(cmd) != 2:
		return None
	if cmd[0].lower() not in ['x', 'o']:
		return None
	if cmd[0].upper() != bot_get_turn():
		return None
	if not cmd[1].isdigit():
		return None
	if int(cmd[1]) <= 0:
		return None
	if int(cmd[1]) > 9:
		return None
	return cmd[0].upper(), int(cmd[1])

def bot_printable_grid():
	global tris
	return str('Grid:' + '\n' + ' '.join(tris[0:3]) + '\n' + ' '.join(tris[3:6]) + '\n' + ' '.join(tris[6:9]))

def bot_play(sym, cell):
	global tris
	global turn
	if tris[cell] == '-':
		tris[cell] = sym
		turn = not turn
		return True
	else:
		return False

def bot_reset():
	global tris
	global turn
	tris = list('-' * 9)
	turn = True

def bot_get_turn():
	global turn
	if turn:
		return 'X'
	else:
		return 'O'

def bot_handle(msg):
	global q
	global turn
	chat_id = msg['chat']['id']
	command = msg['text']

	print('Got command: ' + str(bot_parse_command(command)))

	cmd = bot_parse_command(command)
	if cmd is not None:
		if bot_play(cmd[0], cmd[1]-1):
			q.put([str(cmd[0]), cmd[1]])
			mybot.sendMessage(chat_id, bot_printable_grid())
		else:
			mybot.sendMessage(chat_id, 'Cell already taken!')
			mybot.sendMessage(chat_id, bot_printable_grid())
	elif command == '/grid':
		mybot.sendMessage(chat_id, bot_printable_grid())
	elif command == '/new':
		bot_reset()
		mybot.sendMessage(chat_id, "Ready for a new game")
	else:
		mybot.sendMessage(chat_id, "invalid command")
	mybot.sendMessage(chat_id, 'Now it\'s ' + bot_get_turn() + ' turn.')




class serialMagnet:
	
	ser_port = "/dev/ttyACM0"
	ser_speed = 9600
	ser = None
	
	def __init__(self):
		self.ser = serial.Serial(self.ser_port, self.ser_speed)
		self.off()
		self.off()
	
	def on(self):
		self.ser.write(b"1")
	
	def off(self):
		self.ser.write(b"2")



#------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/ttyUSB0'))
		
	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.xyNode = nodes.compoundNode(self.xAxisNode, self.yAxisNode)

	def initCoordinates(self):
		self.position = state.coordinate(['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(True)])
		self.yAxis = elements.elementChain.forward([elements.microstep.forward(4), elements.stepper.forward(1.8), elements.leadscrew.forward(8), elements.invert.forward(False)])		
		self.stageKinematics = kinematics.direct(2)	#direct drive on all axes
	
	def initFunctions(self):
		self.move = functions.move(virtualMachine = self, virtualNode = self.xyNode, axes = [self.xAxis, self.yAxis], 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.xNode.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]):
		self.position.future.set(position)

	def setSpindleSpeed(self, speedFraction):
		#self.machineControl.pwmRequest(speedFraction)
		pass

def move(machine, dxy, axis=None):
	x_axis = machine.xAxisNode
	y_axis = machine.yAxisNode
	ggg = machine.move(dxy, 0)
	x_status = x_axis.spinStatusRequest()
	y_status = y_axis.spinStatusRequest()
	while x_status['stepsRemaining'] > 0 or y_status['stepsRemaining'] > 0:
		time.sleep(0.001)
		x_status = x_axis.spinStatusRequest()
		y_status = y_axis.spinStatusRequest()

#def move(axis, dxy):
#	machine.move(dxy, 0)
#	status = machine.xAxisNode.spinStatusRequest()
#	# This checks to see if the move is done.
#	while status['stepsRemaining'] > 0:
#		time.sleep(0.001)
#		status = machine.xAxisNode.spinStatusRequest()

def set_origin(machine):
	x_axis = machine.xAxisNode
	y_axis = machine.yAxisNode
	myaxes = ['X', 'Y']
	motors = {'X': x_axis, 'Y': y_axis}
	pos = {'X': 0, 'Y': 1}
	for ax in myaxes:
		while True:
			msg = "Move " + ax + " of n steps (0 to set " + ax + " origin): "
			try:
				curr_pos = machine.getPosition()['position']
				steps = [0, 0]
				s = int(raw_input(msg))
				if s == 0:
					machine.setPosition([0, 0])
					move(machine, steps, motors[ax])
					break
				else:
					steps[pos[ax]] = s
					delta = [curr_pos[0]+steps[0], curr_pos[1]+steps[1]]
					#print(steps, delta)
					move(machine, delta, motors[ax])
			except ValueError:
				pass

def goto_cell(machine, cell):
	cell_size = 66
	safe_dist = 12
	
	n = cell - 1
	move_y = n // 3
	move_x = n % 3
	
	move(stages, [0, 0])
	move(stages, [-safe_dist, -safe_dist])
	move(stages, [move_x * cell_size - safe_dist, -safe_dist])
	move(stages, [move_x * cell_size - safe_dist, move_y * cell_size - safe_dist])
	move(stages, [move_x * cell_size, move_y * cell_size])

def goback_from_cell(machine, cell):
	cell_size = 66
	safe_dist = 12
	
	n = cell - 1
	move_y = n // 3
	move_x = n % 3
	
	move(stages, [move_x * cell_size - safe_dist, move_y * cell_size - safe_dist])
	move(stages, [move_x * cell_size - safe_dist, -safe_dist])
	move(stages, [-safe_dist, -safe_dist])
	move(stages, [0, 0])

def draw_into_cell(machine, cell, magnet, sign):
	box = 33  #35 is perfect
	l = int(box * math.sqrt(2) / 2)
	r = box / math.sqrt(2)
	
	angles = [i/100.0 for i in range(0, int(math.pi*2*100), 10)]
	circle = [[r-r*math.cos(alfa), r-r*math.sin(alfa)] for alfa in angles]
	circle.insert(0, [0, 0])
	circle.append([0, 0])
	cross = [[0, 0], [l, l], [2*l, 2*l], [l, l], [0, 2*l], [l, l], [2*l, 0], [l, l], [0, 0]]	

	if sign == "X":
		goto_cell(machine, cell)
		magnet.on()
		time.sleep(1)
		cp = machine.getPosition()['position']
		cell_zero = [int(cp[0]), int(cp[1])]
		for m in cross:
			move(stages, [cell_zero[0]+m[0], cell_zero[1]+m[1]])
		magnet.off()
		time.sleep(1)
		goback_from_cell(machine, cell)
	elif sign == "O":
		goto_cell(machine, cell)
		magnet.on()
		time.sleep(1)
		cp = machine.getPosition()['position']
		cell_zero = [int(cp[0]), int(cp[1])]
		for m in circle:
			move(stages, [cell_zero[0]+m[0], cell_zero[1]+m[1]])
		magnet.off()
		time.sleep(1)
		goback_from_cell(machine, cell)
	

tris = []
turn = True
q = Queue.Queue()

#------IF RUN DIRECTLY FROM TERMINAL------
if __name__ == '__main__':
	stages = virtualMachine(persistenceFile = "test.vmp")
	magnet = serialMagnet()
	#stages.xyNode.setMotorCurrent(0.7)
	stages.xyNode.setVelocityRequest(5)	
 
	# Goto XY origin and optionaly set new origin
	move(stages, [0, 0])
	set_origin(stages)


	bot_reset()
	mybot = telepot.Bot('#### you secret key ####')
	mybot.message_loop(bot_handle)
	print('I am listening ...')

	try:
		while True:
			if not q.empty():
				remote_cmd = q.get()
				draw_into_cell(stages, remote_cmd[1], magnet, remote_cmd[0])
				q.task_done()
			time.sleep(0.5)
	finally:
		# Goto XY origin
		move(stages, [0, 0])
