forked from BuddhiGamage/chess_robot
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathgame.py
More file actions
396 lines (326 loc) · 14.9 KB
/
game.py
File metadata and controls
396 lines (326 loc) · 14.9 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
import chess
import chess.engine
import chess.svg
import sys
import os
import time
import cv2
from kortex_api.autogen.client_stubs.BaseClientRpc import BaseClient
from kortex_api.autogen.messages import Base_pb2
from move_to_x_y import move_to_cartesian_position as move_arm_to_position
from arm import move_arm_to_chess_pos2,get_real_world_coordinates
import utilities
import argparse
from pick_and_place import pick_chess_piece,place_chess_piece,close_gripper
from photo import capture_image_from_realsense
from chess_board_extract import extract_chessboard
from rf2 import chessboard_to_matrix
from return_move import find_chess_move
base_square = "e6"
# skill_level = 20 # Adjust this value as needed
# skill_level = 5 # Adjust this value as needed
# UCI_Elo = 1500
# Get user input for skill level and UCI_Elo
try:
skill_level = int(input("Enter Skill Level (default is 20): ") or 20)
print(skill_level)
except ValueError:
print("Invalid input. Using default values.")
skill_level = 20
snap="chess_board_snap.jpg"
extracted_board="extracted_chessboard.jpg"
extracted_board_with_no_border="extracted_chessboard_no_border.jpg"
bucket_coordinates_x = 0.258
bucket_coordinates_y = 0.292
home_x=0.13
home_y=-0.069
home_z=0.1
# Parse arguments
parser = argparse.ArgumentParser()
args = utilities.parseConnectionArguments(parser)
sys.path.insert(0, os.path.join(os.path.dirname(__file__), ".."))
# Initialize the chess board
board = chess.Board()
piece_count=32
castling_availability=True
prev_board = [
[9, 7, 8, 10, 11, 8, 7, 9],
[6, 6, 6, 6, 6, 6, 6, 6],
[-1, -1, -1, -1, -1, -1, -1, -1],
[-1, -1, -1, -1, -1, -1, -1, -1],
[-1, -1, -1, -1, -1, -1, -1, -1],
[-1, -1, -1, -1, -1, -1, -1, -1],
[0, 0, 0, 0, 0, 0, 0, 0],
[3, 1, 2, 5, 4, 2, 1, 3]
]
# #test_board
# prev_board = [
# [9, 7, 8, 10, 11, 8, 7, 9],
# [6, 6, 6, 6, 6, 6, 6, 6],
# [-1, -1, -1, -1, -1, -1, -1, -1],
# [-1, -1, -1, -1, -1, -1, -1, -1],
# [-1, -1, -1, -1, -1, -1, -1, -1],
# [-1, -1, -1, -1, -1, -1, -1, -1],
# [0, 0, 0, 0, 0, 0, 0, 0],
# [3, -1, -1, -1, 4, 2, 1, 3]
# ]
# Use the Stockfish engine for AI moves (make sure it's installed and available on your system)
engine_path = "/usr/games/stockfish" # Replace with the actual path to Stockfish
# compare the two lists and check if all numbers greater than 5(which means black positions) are in the same positions in both lists
def check_black_positions(prev_board, new_board):
print(prev_board)
print(new_board)
# Iterate through each row and column
for i in range(len(prev_board)):
for j in range(len(prev_board[i])):
# Check if both lists have numbers > 6 in the same position
if (prev_board[i][j] > 5) or (new_board[i][j] > 5 ):
# if human player replaced the piece with his piece then ignore checking
if(new_board[i][j]<6):
continue
if prev_board[i][j] != new_board[i][j]:
return False
return True
def board_to_matrix(board):
# Map pieces to numeric values
piece_to_value = {
'p': 6, 'r': 9, 'n': 7, 'b': 8, 'q': 10, 'k': 11, # Black pieces
'P': 0, 'R': 3, 'N': 1, 'B': 2, 'Q': 5, 'K': 4, # White pieces
None: -1 # Empty squares
}
# Convert the board to a matrix
matrix = []
for square in chess.SQUARES: # Loop through all squares (a1-h8)
piece = board.piece_at(square) # Get the piece on the square
piece_symbol = piece.symbol() if piece else None # Get piece symbol or None
if square % 8 == 0: # Start of a new row
matrix.append([]) # Add a new row to the matrix
matrix[-1].append(piece_to_value[piece_symbol]) # Add the value to the matrix
# Reverse rows to place black pieces on top
matrix.reverse()
return matrix
# Create connection to the device and get the router
with utilities.DeviceConnection.createTcpConnection(args) as router:
base = BaseClient(router)
# with chess.engine.SimpleEngine.popen_uci(engine_path) as engine:
engine = chess.engine.SimpleEngine.popen_uci(engine_path)
# Configure the engine with the user inputs or defaults
engine.configure({
"Skill Level": skill_level
})
print("Welcome to Chess! Enter your moves in UCI notation (e.g., e2e4). Type 'quit' to exit.")
move_arm_to_position(base, home_x, home_y, home_z) # home pose before taking the snap of the chess board
close_gripper(base)
time.sleep(3)
while not board.is_game_over():
# Display the board
print(board)
# oppent will play as white and do the first move and press n.
# user_input = input("Press enter after move")
# move_arm_to_chess_pos2(base,base_square)
# time.sleep(1)
# generate fen from the image
move_arm_to_position(base, home_x, home_y, home_z) # home pose before taking the snap of the chess board
time.sleep(3)
capture_image_from_realsense(snap) # taking the snap
img_board=extract_chessboard(snap)
cv2.imwrite(extracted_board, img_board)
current_board,count=chessboard_to_matrix(extracted_board)
while count!=piece_count and count!=piece_count-1:
print(piece_count)
capture_image_from_realsense(snap) # taking the snap
img_board=extract_chessboard(snap)
cv2.imwrite(extracted_board, img_board)
current_board,count=chessboard_to_matrix(extracted_board)
# Get the human player's move
print(prev_board)
print(current_board)
# Check if they are the same
if prev_board == current_board:
print("Player's turn")
continue
human_move,castling_availability=find_chess_move(prev_board,current_board,castling_availability)
if human_move==None:
print("Move did not Capture. Try again")
continue
print("human move: ", human_move)
print('castling availability: '+str(castling_availability))
human_move_prueba = chess.Move.from_uci(human_move)
try:
# Parse and apply the human player's move
if human_move_prueba in board.legal_moves:
if board.is_capture(human_move_prueba):
piece_count-=1
print('capture move by human')
# quit()
board.push(human_move_prueba)
elif chess.Move.from_uci(human_move + "q") in board.legal_moves:
# Loop until a valid promotion piece is provided
while True:
promotion_piece = input("Pawn promotion! Choose a piece (q, r, b, n): ").lower()
if promotion_piece in ["q", "r", "b", "n"]:
break # Valid input
else:
print("Invalid input. Please choose q (queen), r (rook), b (bishop), or n (knight).")
human_move += promotion_piece
human_move_prueba = chess.Move.from_uci(human_move)
if human_move_prueba in board.legal_moves:
if board.is_capture(human_move_prueba):
piece_count-=1
print('capture move by human')
# quit()
print("Pawn is promoted to: "+promotion_piece)
board.push(human_move_prueba)
else:
print("Illegal move. Try again.")
continue
else:
print("Illegal move. Try again.")
continue
except ValueError:
print("Invalid UCI format. Try again.")
continue
# print(board)
# if board.is_capture(human_move):
# piece_count-=1
# print('capture move by human')
# quit()
# if(is_capture):
# piece_count-=1
# print(is_capture)
# print('quit in if')
# quit()
# print(human_move)
# Check if the game is over after the human move
if board.is_game_over():
break
# Let the AI make its move
print("AI is thinking...")
result = engine.play(board, chess.engine.Limit(time=0.1)) # AI moves with a 0.1-second time limit
# Extract the move details
ai_move = result.move
print("AI move:", result.move)
# # Determine the given move is a castling move
# black_kingside = chess.Move.from_uci("e8g8") # Black kingside castling
# black_queenside = chess.Move.from_uci("e8c8") # Black queenside castling
# ai_move = black_kingside
# ai_move = chess.Move.from_uci("g8h6")
# Determine the source and target squares of the move
source_square = ai_move.from_square # Starting square index (0-63)
target_square = ai_move.to_square # Ending square index (0-63)
# Convert to algebraic notation (e.g., 'e2', 'e4')
source_pos = chess.square_name(source_square) # e.g., 'e2'
target_pos = chess.square_name(target_square) # e.g., 'e4'
# Check if the target square contains an opponent's piece (indicates a capture)
# capture_move = chess.Move.from_uci(str(ai_move)) # check capturing
if board.is_capture(ai_move):
piece_count-=1
if board.is_en_passant(ai_move):
captured_square = chess.square(chess.square_file(ai_move.to_square), chess.square_rank(ai_move.from_square))
else:
captured_square = ai_move.to_square
captured_square = chess.square_name(captured_square)
print(f"The AI move captures a piece on {captured_square}.")
# Move the arm to the captured piece's position (captured_square)
# move_arm_to_chess_pos2(base,base_square)
# move_arm_to_position(base, home_x, home_y, home_z) # home pose
# time.sleep(1)
_,_,target_z = get_real_world_coordinates(captured_square)
move_arm_to_chess_pos2(base, captured_square)
time.sleep(3)
pick_chess_piece(base,target_z)
# Move the arm to the bucket (replace with actual bucket coordinates)
# bucket_coordinates = 'h1' # Example bucket position (change as needed)
move_arm_to_position(base,bucket_coordinates_x,bucket_coordinates_y)
time.sleep(3)
place_chess_piece(base,target_z=0.14) # Example place
# check arm did the move
capture_image_from_realsense(snap) # taking the snap
img_board=extract_chessboard(snap)
cv2.imwrite(extracted_board, img_board)
_,count=chessboard_to_matrix(extracted_board)
while count!=piece_count:
if(count-1==piece_count):
print(f"please help me to capture the piece: {captured_square}")
print(piece_count)
capture_image_from_realsense(snap) # taking the snap
img_board=extract_chessboard(snap)
cv2.imwrite(extracted_board, img_board)
current_board,count=chessboard_to_matrix(extracted_board)
# Perform the AI's move
# move_arm_to_chess_pos2(base,base_square)
# move_arm_to_position(base, home_x, home_y, home_z) # home pose before taking the snap of the chess board
# time.sleep(1)
_,_,target_z = get_real_world_coordinates(source_pos)
print(target_z)
move_arm_to_chess_pos2(base,source_pos)
time.sleep(3)
pick_chess_piece(base,target_z) # Example pick
# move_arm_to_chess_pos2(base,base_square)
# move_arm_to_position(base, home_x, home_y, home_z) # home pose before taking the snap of the chess board
# time.sleep(1)
move_arm_to_chess_pos2(base,target_pos)
time.sleep(3)
place_chess_piece(base,target_z) # Example place
# Check if the move is kingside or queenside castling
if board.is_castling(ai_move):
if board.is_kingside_castling(ai_move):
# Rook's move: h8 -> f8
rook_source_pos = 'h8'
rook_target_pos = 'f8'
elif board.is_queenside_castling(ai_move):
# Rook's move: a8 -> d8
rook_source_pos = 'a8'
rook_target_pos = 'd8'
# Perform the AI's move
# move_arm_to_chess_pos2(base,base_square)
# time.sleep(1)
_,_,target_z = get_real_world_coordinates(rook_source_pos)
print(target_z)
move_arm_to_chess_pos2(base,rook_source_pos)
time.sleep(3)
pick_chess_piece(base,target_z) # pick
# move_arm_to_chess_pos2(base,base_square)
# time.sleep(1)
move_arm_to_chess_pos2(base,rook_target_pos)
time.sleep(3)
place_chess_piece(base,target_z) # place
move_arm_to_position(base, home_x, home_y, home_z) # home pose before taking the snap of the chess board
time.sleep(3)
# Push the move on the board to update the state
board.push(ai_move)
# Convert the board to a matrix
prev_board = board_to_matrix(board)
# check arm did the move
capture_image_from_realsense(snap) # taking the snap
img_board=extract_chessboard(snap)
cv2.imwrite(extracted_board, img_board)
current_board,count=chessboard_to_matrix(extracted_board)
print(current_board)
while count!=piece_count and count!=piece_count-1:
print(piece_count)
capture_image_from_realsense(snap) # taking the snap
img_board=extract_chessboard(snap)
cv2.imwrite(extracted_board, img_board)
current_board,count=chessboard_to_matrix(extracted_board)
arm_move_state=check_black_positions(prev_board,current_board)
print("Arm movement state: "+str(arm_move_state))
# quit()
while (arm_move_state==False):
print(f"Can you please fix my move to: {ai_move}")
time.sleep(2)
# check arm did the move
capture_image_from_realsense(snap) # taking the snap
img_board=extract_chessboard(snap)
cv2.imwrite(extracted_board, img_board)
current_board,count=chessboard_to_matrix(extracted_board)
while count!=piece_count and count!=piece_count-1:
print(piece_count)
capture_image_from_realsense(snap) # taking the snap
img_board=extract_chessboard(snap)
cv2.imwrite(extracted_board, img_board)
current_board,count=chessboard_to_matrix(extracted_board)
arm_move_state = check_black_positions(prev_board,current_board)
# Display the game result
print("Game over!")
print("Result:", board.result())