feat: removed useless function
This commit is contained in:
parent
248e8dd073
commit
aebc157507
32
control.py
32
control.py
@ -241,7 +241,6 @@ def convert_to_robot(positions):
|
|||||||
counter += 1
|
counter += 1
|
||||||
if counter % 2 != 0:
|
if counter % 2 != 0:
|
||||||
return
|
return
|
||||||
print(positions)
|
|
||||||
index = [
|
index = [
|
||||||
11, 12, 13,
|
11, 12, 13,
|
||||||
41, 42, 43,
|
41, 42, 43,
|
||||||
@ -254,8 +253,6 @@ def convert_to_robot(positions):
|
|||||||
for i in range(len(positions)):
|
for i in range(len(positions)):
|
||||||
value = int(512 + positions[i] * 150 * dir[i])
|
value = int(512 + positions[i] * 150 * dir[i])
|
||||||
packetHandler.write2ByteTxOnly(portHandler, index[i], ADDR_GOAL_POSITION, value)
|
packetHandler.write2ByteTxOnly(portHandler, index[i], ADDR_GOAL_POSITION, value)
|
||||||
# packetHandler.writeTxOnly(portHandler, index[i], ADDR_GOAL_POSITION, 2,
|
|
||||||
# bytes(value))
|
|
||||||
|
|
||||||
|
|
||||||
def stand(x1, y1, x2, y2):
|
def stand(x1, y1, x2, y2):
|
||||||
@ -497,34 +494,5 @@ def dino_naive(t, speed_x, speed_y, hz, hy, hx):
|
|||||||
return legs(real_position)
|
return legs(real_position)
|
||||||
|
|
||||||
|
|
||||||
def robot_input():
|
|
||||||
print("Send motors wave (press enter)")
|
|
||||||
input()
|
|
||||||
for id in ids:
|
|
||||||
packetHandler.write2ByteTxRx(portHandler, id, ADDR_GOAL_POSITION, 512)
|
|
||||||
input()
|
|
||||||
angle = [512, 624, 400, 512, 624, 400]
|
|
||||||
for id in range(1, 7):
|
|
||||||
packetHandler.write2ByteTxRx(portHandler, id * 10 + 1, ADDR_GOAL_POSITION, angle[id - 1])
|
|
||||||
input()
|
|
||||||
|
|
||||||
# Dino mode
|
|
||||||
packetHandler.write2ByteTxRx(portHandler, 12, ADDR_GOAL_POSITION, 650)
|
|
||||||
packetHandler.write2ByteTxRx(portHandler, 42, ADDR_GOAL_POSITION, 650)
|
|
||||||
packetHandler.write2ByteTxRx(portHandler, 43, ADDR_GOAL_POSITION, 400)
|
|
||||||
|
|
||||||
input()
|
|
||||||
for id in ids:
|
|
||||||
packetHandler.write2ByteTxRx(portHandler, id, ADDR_GOAL_POSITION, 512)
|
|
||||||
# t = 0.0
|
|
||||||
# while True:
|
|
||||||
# print("Send motors wave (press enter)")
|
|
||||||
# angle = 512 + int(50 * np.sin(t))
|
|
||||||
# print(angle)
|
|
||||||
# packetHandler.write2ByteTxRx(portHandler, 53, ADDR_GOAL_POSITION, angle)
|
|
||||||
# time.sleep(0.001)
|
|
||||||
# t += 0.01
|
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
print("N'exécutez pas ce fichier, mais simulator.py")
|
print("N'exécutez pas ce fichier, mais simulator.py")
|
||||||
|
Loading…
x
Reference in New Issue
Block a user