Compare commits
6 Commits
90d08671d9
...
main
Author | SHA1 | Date | |
---|---|---|---|
0b23964d25 | |||
aebc157507 | |||
248e8dd073 | |||
561b2f70a2 | |||
25af55d963 | |||
6b0f2c2170 |
295
control.py
295
control.py
@ -1,14 +1,15 @@
|
|||||||
import logging
|
import logging
|
||||||
import math
|
|
||||||
import numpy as np
|
import numpy as np
|
||||||
from math import *
|
from math import *
|
||||||
from logs import *
|
from logs import *
|
||||||
|
from dynamixel_sdk import *
|
||||||
from xbox import *
|
from xbox import *
|
||||||
import time
|
import time
|
||||||
|
|
||||||
# DEBUG
|
# DEBUG
|
||||||
LEGS_LOG_LEVEL = logging.INFO
|
LEGS_LOG_LEVEL = logging.WARNING
|
||||||
CONTROLLER_LOG_LEVEL = logging.INFO
|
CONTROLLER_LOG_LEVEL = logging.CRITICAL
|
||||||
# Variables configurations
|
# Variables configurations
|
||||||
|
|
||||||
l1h = 0.049
|
l1h = 0.049
|
||||||
@ -40,25 +41,57 @@ controllerLogger = setup_logger("Controller", CONTROLLER_LOG_LEVEL)
|
|||||||
# Initialize controller
|
# Initialize controller
|
||||||
xbox = Xbox(controllerLogger)
|
xbox = Xbox(controllerLogger)
|
||||||
CONTROLLER_MODE = xbox.initialized
|
CONTROLLER_MODE = xbox.initialized
|
||||||
xbox.mode_count = 4
|
xbox.mode_count = 5
|
||||||
|
|
||||||
neutral_position = np.array([
|
neutral_position = np.array([
|
||||||
[0.1, 0.15, -0.15],
|
[0.08, 0.16, -0.12],
|
||||||
[-0.1, 0.15, -0.15],
|
[-0.08, 0.16, -0.12],
|
||||||
[-0.2, -0.00, -0.15],
|
[-0.2, -0.00, -0.12],
|
||||||
[-0.1, -0.15, -0.15],
|
[-0.08, -0.16, -0.12],
|
||||||
[0.1, -0.15, -0.15],
|
[0.08, -0.16, -0.12],
|
||||||
[0.2, 0, -0.15]
|
[0.2, 0, -0.12]
|
||||||
])
|
])
|
||||||
|
|
||||||
|
REAL = 0
|
||||||
|
|
||||||
|
# Robot setup
|
||||||
|
if REAL == 1:
|
||||||
|
try:
|
||||||
|
portHandler = PortHandler("/dev/ttyUSB0")
|
||||||
|
except:
|
||||||
|
portHandler = PortHandler("/dev/ttyUSB1")
|
||||||
|
|
||||||
|
packetHandler = PacketHandler(1.0)
|
||||||
|
|
||||||
|
portHandler.openPort()
|
||||||
|
portHandler.setBaudRate(1000000)
|
||||||
|
ADDR_GOAL_POSITION = 30
|
||||||
|
|
||||||
|
ids = []
|
||||||
|
for id in range(0, 100):
|
||||||
|
model_number, result, error = packetHandler.ping(portHandler, id)
|
||||||
|
if model_number == 12:
|
||||||
|
print(f"Found AX-12 with id: {id}")
|
||||||
|
ids.append(id)
|
||||||
|
time.sleep(0.01)
|
||||||
|
if len(ids) != 18:
|
||||||
|
legsLogger.error("Not all motor found. Press enter to continue")
|
||||||
|
input()
|
||||||
|
|
||||||
|
|
||||||
def interpol2(point2, point1, t):
|
def interpol2(point2, point1, t):
|
||||||
|
"""
|
||||||
|
Linear interpolation between two points in space
|
||||||
|
"""
|
||||||
x1, y1, z1 = point1
|
x1, y1, z1 = point1
|
||||||
x2, y2, z2 = point2
|
x2, y2, z2 = point2
|
||||||
return t * x1 + (1 - t) * x2, t * y1 + (1 - t) * y2, t * z1 + (1 - t) * z2
|
return t * x1 + (1 - t) * x2, t * y1 + (1 - t) * y2, t * z1 + (1 - t) * z2
|
||||||
|
|
||||||
|
|
||||||
def get_current_step(t, step_duration, movement_duration):
|
def get_current_step(t, step_duration, movement_duration):
|
||||||
|
"""
|
||||||
|
helper function used to calculate the current step of the movement i.e. what part of the movement.
|
||||||
|
"""
|
||||||
time_passed = 0
|
time_passed = 0
|
||||||
for i in range(len(step_duration)):
|
for i in range(len(step_duration)):
|
||||||
time_passed += step_duration[i]
|
time_passed += step_duration[i]
|
||||||
@ -67,6 +100,9 @@ def get_current_step(t, step_duration, movement_duration):
|
|||||||
|
|
||||||
|
|
||||||
def get_current_step_advancement(t, movement_duration, step_duration, current_step):
|
def get_current_step_advancement(t, movement_duration, step_duration, current_step):
|
||||||
|
"""
|
||||||
|
helper function used to calculate the current advancement of the movement step i.e. the percentage of progression of said movement.
|
||||||
|
"""
|
||||||
current_step = get_current_step(t, step_duration, movement_duration)
|
current_step = get_current_step(t, step_duration, movement_duration)
|
||||||
t = t % movement_duration
|
t = t % movement_duration
|
||||||
for i in range(0, current_step):
|
for i in range(0, current_step):
|
||||||
@ -76,6 +112,7 @@ def get_current_step_advancement(t, movement_duration, step_duration, current_st
|
|||||||
|
|
||||||
def inverse(x, y, z):
|
def inverse(x, y, z):
|
||||||
"""
|
"""
|
||||||
|
Calculate the angle of each motor to have the end of the feet at a specified position
|
||||||
"""
|
"""
|
||||||
# Dimensions (m)
|
# Dimensions (m)
|
||||||
z += l1v
|
z += l1v
|
||||||
@ -83,32 +120,29 @@ def inverse(x, y, z):
|
|||||||
theta0 = atan2(y, x)
|
theta0 = atan2(y, x)
|
||||||
|
|
||||||
l = sqrt((sqrt(x ** 2 + y ** 2) - l1) ** 2 + z ** 2)
|
l = sqrt((sqrt(x ** 2 + y ** 2) - l1) ** 2 + z ** 2)
|
||||||
# l = sqrt((x - l1h*cos(theta0)) ** 2 + (y - l1h*sin(theta0)) ** 2 + (z + l1v) ** 2)
|
|
||||||
|
|
||||||
param2 = -1 * (-(l ** 2) + l2 ** 2 + l3 ** 2) / (2 * l2 * l3)
|
param2 = -1 * (-(l ** 2) + l2 ** 2 + l3 ** 2) / (2 * l2 * l3)
|
||||||
|
|
||||||
if param2 > 1 or param2 < -1:
|
if param2 > 1 or param2 < -1:
|
||||||
print("\033[94m" + f"Tentative d'acces a une position impossible (param2) ({x}, {y}, {z})" + "\033[0m")
|
legsLogger.warning("fTentative d'acces a une position impossible (param2) ({x}, {y}, {z})")
|
||||||
param2 = 1 if param2 > 1 else -1
|
param2 = 1 if param2 > 1 else -1
|
||||||
|
|
||||||
theta2 = acos(param2)
|
theta2 = acos(param2)
|
||||||
|
|
||||||
param1 = (-l3 ** 2 + l2 ** 2 + l ** 2) / (2 * l2 * l)
|
param1 = (-l3 ** 2 + l2 ** 2 + l ** 2) / (2 * l2 * l)
|
||||||
if param1 > 1 or param1 < -1:
|
if param1 > 1 or param1 < -1:
|
||||||
print("\033[94m" + f"Tentative d'acces a une position impossible (param1) ({x}, {y}, {z})" + "\033[0m")
|
legsLogger.warning(f"Tentative d'acces a une position impossible (param1) ({x}, {y}, {z})")
|
||||||
param1 = 1 if param1 > 1 else -1
|
param1 = 1 if param1 > 1 else -1
|
||||||
|
|
||||||
theta1 = acos(param1) + asin(z / l)
|
theta1 = acos(param1) + asin(z / l)
|
||||||
|
|
||||||
# return [-theta0, theta1, theta2]
|
|
||||||
angle1 = atan(l2v / l2h)
|
angle1 = atan(l2v / l2h)
|
||||||
return [-theta0, theta1 + angle1, theta2 + angle1 - pi / 2 + atan(l3h / l3v)]
|
return [-theta0, theta1 + angle1, theta2 + angle1 - pi / 2 + atan(l3h / l3v)]
|
||||||
# return [0, angle1 , angle1 -pi/2 + atan(l3h/l3v)]
|
|
||||||
|
|
||||||
|
|
||||||
def legs(targets_robot):
|
def legs(targets_robot):
|
||||||
"""
|
"""
|
||||||
takes a list of target and offsets it to be in the legs referential
|
takes a list of target and offsets them to be in the legs referential
|
||||||
"""
|
"""
|
||||||
|
|
||||||
targets = [0] * 18
|
targets = [0] * 18
|
||||||
@ -137,7 +171,72 @@ def legs(targets_robot):
|
|||||||
return targets
|
return targets
|
||||||
|
|
||||||
|
|
||||||
|
def normalize(matrix, slider_max, speed):
|
||||||
|
return (matrix / slider_max) * speed
|
||||||
|
|
||||||
|
|
||||||
|
counter = 0
|
||||||
|
|
||||||
|
|
||||||
|
def convert_to_robot(positions):
|
||||||
|
"""
|
||||||
|
Send a robot position to the real robot.
|
||||||
|
"""
|
||||||
|
global counter
|
||||||
|
counter += 1
|
||||||
|
if counter % 2 != 0:
|
||||||
|
return
|
||||||
|
index = [
|
||||||
|
11, 12, 13,
|
||||||
|
41, 42, 43,
|
||||||
|
21, 22, 23,
|
||||||
|
51, 52, 53,
|
||||||
|
61, 62, 63,
|
||||||
|
31, 32, 33]
|
||||||
|
dir = [-1] * 18
|
||||||
|
|
||||||
|
for i in range(len(positions)):
|
||||||
|
value = int(512 + positions[i] * 150 * dir[i])
|
||||||
|
packetHandler.write2ByteTxOnly(portHandler, index[i], ADDR_GOAL_POSITION, value)
|
||||||
|
|
||||||
|
|
||||||
|
def walk(t, sx, sy, sr):
|
||||||
|
"""
|
||||||
|
Choose the algorithm depending on input of xbox controller
|
||||||
|
"""
|
||||||
|
xboxdata = xbox.get_data()
|
||||||
|
if xbox.initialized:
|
||||||
|
max_slider = 0.200
|
||||||
|
controllerLogger.debug(xboxdata)
|
||||||
|
if xbox.mode == 0:
|
||||||
|
positions = static()
|
||||||
|
elif xbox.mode == 1:
|
||||||
|
positions = jump(xboxdata["y2"])
|
||||||
|
elif xbox.mode == 2:
|
||||||
|
positions = dino_naive(t, max_slider * xboxdata["y1"], max_slider * xboxdata["x1"],
|
||||||
|
max_slider * xboxdata["y2"],
|
||||||
|
max_slider * xboxdata["x2"], max_slider * (xboxdata["r2"] + 1))
|
||||||
|
elif xbox.mode == 3:
|
||||||
|
positions = naive_walk(t, max_slider * xboxdata["x1"], max_slider * xboxdata["y1"])
|
||||||
|
elif xbox.mode == 4:
|
||||||
|
positions = walk_v2(t, max_slider * xboxdata["y1"], -1 * max_slider * xboxdata["x1"],
|
||||||
|
xboxdata["x2"] * max_slider,
|
||||||
|
max_slider * xboxdata["y2"])
|
||||||
|
# print(positions)
|
||||||
|
if REAL == 1:
|
||||||
|
convert_to_robot(positions)
|
||||||
|
|
||||||
|
return positions
|
||||||
|
else:
|
||||||
|
return walk_v2(t, sx, sy, sr, None)
|
||||||
|
|
||||||
|
|
||||||
|
# different move algorithm
|
||||||
|
|
||||||
def naive_walk(t, speed_x, speed_y):
|
def naive_walk(t, speed_x, speed_y):
|
||||||
|
"""
|
||||||
|
First version of walk, using triangle for each step
|
||||||
|
"""
|
||||||
slider_max = 0.200
|
slider_max = 0.200
|
||||||
|
|
||||||
real_position = np.copy(neutral_position)
|
real_position = np.copy(neutral_position)
|
||||||
@ -203,89 +302,44 @@ def naive_walk(t, speed_x, speed_y):
|
|||||||
return legs(real_position)
|
return legs(real_position)
|
||||||
|
|
||||||
|
|
||||||
def translate(tx, ty, tz):
|
|
||||||
return np.array([
|
|
||||||
[1.0, 0.0, 0.0, tx],
|
|
||||||
[0.0, 1.0, 0.0, ty],
|
|
||||||
[0.0, 0.0, 1.0, tz],
|
|
||||||
[0.0, 0.0, 0.0, 1.0],
|
|
||||||
])
|
|
||||||
|
|
||||||
|
|
||||||
def normalize(matrix, slider_max, speed):
|
|
||||||
return (matrix / slider_max) * speed
|
|
||||||
|
|
||||||
|
|
||||||
def Rx(alpha):
|
|
||||||
return np.array([
|
|
||||||
[1.0, 0.0, 0.0, 0.0],
|
|
||||||
[0.0, np.cos(alpha), -np.sin(alpha), 0.0],
|
|
||||||
[0.0, np.sin(alpha), np.cos(alpha), 0.0],
|
|
||||||
[0.0, 0.0, 0.0, 1.0],
|
|
||||||
])
|
|
||||||
|
|
||||||
|
|
||||||
def Ry(alpha):
|
|
||||||
return np.array([
|
|
||||||
[np.cos(alpha), 0.0, -np.sin(alpha), 0.0],
|
|
||||||
[0.0, 1.0, 0.0, 0.0],
|
|
||||||
[np.sin(alpha), 0.0, np.cos(alpha), 0.0],
|
|
||||||
[0.0, 0.0, 0.0, 1.0],
|
|
||||||
])
|
|
||||||
|
|
||||||
|
|
||||||
def Rz(alpha):
|
|
||||||
return np.array([
|
|
||||||
[np.cos(alpha), -np.sin(alpha), 0.0, 0.0],
|
|
||||||
[np.sin(alpha), np.cos(alpha), 0.0, 0.0],
|
|
||||||
[0.0, 0.0, 1.0, 0.0],
|
|
||||||
[0.0, 0.0, 0.0, 1.0],
|
|
||||||
])
|
|
||||||
|
|
||||||
|
|
||||||
def walk(t, sx, sy, sr):
|
|
||||||
xboxdata = xbox.get_data()
|
|
||||||
max_slider = 0.200
|
|
||||||
controllerLogger.debug(xboxdata)
|
|
||||||
if xbox.mode == 0:
|
|
||||||
return static()
|
|
||||||
elif xbox.mode == 1:
|
|
||||||
return jump(xboxdata["y2"])
|
|
||||||
elif xbox.mode == 2:
|
|
||||||
return dino_naive(t, max_slider * xboxdata["y1"], max_slider * xboxdata["x1"], max_slider * xboxdata["y2"],
|
|
||||||
max_slider * xboxdata["x2"], max_slider * (xboxdata["r2"] + 1))
|
|
||||||
elif xbox.mode == 3:
|
|
||||||
return dev(t, max_slider * xboxdata["y1"], max_slider * xboxdata["x1"], max_slider * xboxdata["y2"],
|
|
||||||
max_slider * xboxdata["x2"])
|
|
||||||
else:
|
|
||||||
return naive_walk(t, max_slider * xboxdata["x1"], max_slider * xboxdata["y1"])
|
|
||||||
|
|
||||||
|
|
||||||
def static():
|
def static():
|
||||||
|
"""
|
||||||
|
Function to have the robot stand at the neutral position
|
||||||
|
"""
|
||||||
return legs(neutral_position)
|
return legs(neutral_position)
|
||||||
|
|
||||||
|
|
||||||
# Walk V2
|
# Walk V2
|
||||||
def dev(t, x1, y1, x2, y2):
|
def walk_v2(t, speed_x, speed_y, speed_r, y2):
|
||||||
|
"""
|
||||||
|
Second version of the walking algorithm, using circle for each leg
|
||||||
|
This is the main algorithm.
|
||||||
|
"""
|
||||||
|
max_dist = 0.3
|
||||||
|
|
||||||
def get_rotation_center(speed_x, speed_y, theta_point):
|
def get_rotation_center(speed_x, speed_y, theta_point):
|
||||||
direction = np.array([-speed_y, speed_x])
|
"""
|
||||||
return direction / max(0.001, theta_point)
|
Helper function that calculate the center of rotation of the robot based on the current parameters
|
||||||
|
"""
|
||||||
|
norm = sqrt(speed_x ** 2 + speed_y ** 2)
|
||||||
|
|
||||||
x0, y0 = get_rotation_center(x1, y1, x2)
|
r = 1000 if theta_point == 0 else norm / theta_point
|
||||||
|
if norm != 0:
|
||||||
print(x0, y0)
|
return np.array([speed_y, -speed_x]) / norm * r
|
||||||
|
else:
|
||||||
num_patte = 6
|
return 0, 0
|
||||||
|
|
||||||
|
center_x, center_y = get_rotation_center(speed_x, speed_y, speed_r)
|
||||||
|
legsLogger.debug(f"rotation center: center_x: {center_x}, center_y: {center_y}")
|
||||||
real_position = np.copy(neutral_position)
|
real_position = np.copy(neutral_position)
|
||||||
|
|
||||||
movement_z = np.array([
|
movement_z = np.array([
|
||||||
[0, 0, 0.02],
|
[0, 0, 0.03],
|
||||||
[0, 0, -0.01],
|
[0, 0, -0.02],
|
||||||
[0, 0, -0.01]
|
[0, 0, -0.02]
|
||||||
])
|
])
|
||||||
|
|
||||||
step_duration = np.array([0.05, 0.3, 0.05])
|
step_duration = np.array([0.15, 0.3, 0.15])
|
||||||
|
|
||||||
step_count = len(movement_z)
|
step_count = len(movement_z)
|
||||||
movement_duration = np.sum(step_duration)
|
movement_duration = np.sum(step_duration)
|
||||||
@ -296,15 +350,22 @@ def dev(t, x1, y1, x2, y2):
|
|||||||
def get_next_step(t):
|
def get_next_step(t):
|
||||||
return floor((get_current_step(t, step_duration, movement_duration) + 1) % step_count)
|
return floor((get_current_step(t, step_duration, movement_duration) + 1) % step_count)
|
||||||
|
|
||||||
offsets = np.array([0, 1 / 2, 2 / 3, 0, 1 / 2, 2 / 3]) * movement_duration # offset between each leg
|
offsets = np.array([0, 1 / 3, 2 / 3, 0, 1 / 3, 2 / 3]) * movement_duration # offset between each leg
|
||||||
assert len(offsets) == num_patte, f"all offsets must be set, currently, {len(offsets)}/{num_patte} have them"
|
assert len(offsets) == num_patte, f"all offsets must be set, currently, {len(offsets)}/{num_patte} have them"
|
||||||
|
|
||||||
|
# used to cap the speed to a max
|
||||||
|
max_radius = 0
|
||||||
|
for patte in range(num_patte):
|
||||||
|
x1, y1 = real_position[patte][0], real_position[patte][1]
|
||||||
|
circle_radius = sqrt((center_x - x1) ** 2 + (center_y - y1) ** 2)
|
||||||
|
max_radius = max(max_radius, circle_radius)
|
||||||
|
|
||||||
for patte in range(num_patte):
|
for patte in range(num_patte):
|
||||||
time = t + offsets[patte]
|
time = t + offsets[patte]
|
||||||
mov_index_start = get_current_step(time, step_duration, movement_duration)
|
mov_index_start = get_current_step(time, step_duration, movement_duration)
|
||||||
mov_index_end = get_next_step(time)
|
mov_index_end = get_next_step(time)
|
||||||
|
|
||||||
step_adv = get_current_step_advancement(t, movement_duration, step_duration, mov_index_start)
|
step_adv = get_current_step_advancement(time, movement_duration, step_duration, mov_index_start)
|
||||||
|
|
||||||
mov_start_z = movement_z[mov_index_start]
|
mov_start_z = movement_z[mov_index_start]
|
||||||
mov_end_z = movement_z[mov_index_end]
|
mov_end_z = movement_z[mov_index_end]
|
||||||
@ -316,28 +377,48 @@ def dev(t, x1, y1, x2, y2):
|
|||||||
real_position[patte][1],
|
real_position[patte][1],
|
||||||
real_position[patte][2]) = interpol2(mov_start, mov_end, step_adv)
|
real_position[patte][2]) = interpol2(mov_start, mov_end, step_adv)
|
||||||
|
|
||||||
dthteta = x2 * 2
|
|
||||||
|
|
||||||
theta = dthteta * (step_adv - 0.5)
|
|
||||||
# theta = 0
|
|
||||||
print(theta)
|
|
||||||
# rotating the vector
|
|
||||||
x1, y1 = real_position[patte][0], real_position[patte][1]
|
x1, y1 = real_position[patte][0], real_position[patte][1]
|
||||||
print(f"x1: {x1}, y1: {y1}")
|
|
||||||
x1t, y1t = x1 - x0, y1 - y0
|
|
||||||
x2t, y2t = x1t * cos(theta) + y1t * sin(theta), x1t * sin(theta) + y1t * cos(theta)
|
|
||||||
x2, y2 = x2t + x0, y2t + y0
|
|
||||||
print(f"x2: {x2}, y2: {y2}")
|
|
||||||
if mov_index_start == 1:
|
|
||||||
# theta += time
|
|
||||||
# xp = d * cos(theta) + real_position[patte][0]
|
|
||||||
real_position[patte][0] = x2
|
|
||||||
real_position[patte][1] = y2
|
|
||||||
|
|
||||||
|
circle_radius = sqrt((center_x - x1) ** 2 + (center_y - y1) ** 2)
|
||||||
|
cur_theta = acos((x1 - center_x) / circle_radius)
|
||||||
|
|
||||||
|
if y1 < center_y:
|
||||||
|
cur_theta *= -1
|
||||||
|
if speed_r != 0:
|
||||||
|
speed = sqrt(speed_x ** 2 + speed_y ** 2) * (speed_r / abs(speed_r))
|
||||||
|
else:
|
||||||
|
speed = sqrt(speed_x ** 2 + speed_y ** 2)
|
||||||
|
|
||||||
|
if speed == 0:
|
||||||
|
speed = speed_r
|
||||||
|
dthteta = speed * (1 / max_radius * max_dist)
|
||||||
|
legsLogger.info(f"speed: {speed}, dthteta: {dthteta}")
|
||||||
|
if mov_index_start == 0:
|
||||||
|
# midair part 1
|
||||||
|
theta_offset = dthteta * (- step_adv)
|
||||||
|
elif mov_index_start == 1:
|
||||||
|
# moving part
|
||||||
|
theta_offset = dthteta * (step_adv - 0.5) * 2
|
||||||
|
else:
|
||||||
|
# midair part 1
|
||||||
|
theta_offset = dthteta * (1 - step_adv)
|
||||||
|
wanted_theta = cur_theta + theta_offset
|
||||||
|
|
||||||
|
wanted_x = center_x + circle_radius * cos(wanted_theta)
|
||||||
|
wanted_y = center_y + circle_radius * sin(wanted_theta)
|
||||||
|
|
||||||
|
real_position[patte][0] = wanted_x
|
||||||
|
real_position[patte][1] = wanted_y
|
||||||
|
|
||||||
|
if REAL:
|
||||||
return legs(real_position)
|
return legs(real_position)
|
||||||
|
return legs(real_position), [center_x, center_y]
|
||||||
|
|
||||||
|
|
||||||
def jump(sy):
|
def jump(sy):
|
||||||
|
"""
|
||||||
|
Make the robot jump (at least we wished)
|
||||||
|
"""
|
||||||
offset = np.array([
|
offset = np.array([
|
||||||
[0, 0, -0.15],
|
[0, 0, -0.15],
|
||||||
[0, 0, -0.15],
|
[0, 0, -0.15],
|
||||||
@ -350,8 +431,10 @@ def jump(sy):
|
|||||||
return legs(neutral_position + offset)
|
return legs(neutral_position + offset)
|
||||||
|
|
||||||
|
|
||||||
# based on walk V1
|
|
||||||
def dino_naive(t, speed_x, speed_y, hz, hy, hx):
|
def dino_naive(t, speed_x, speed_y, hz, hy, hx):
|
||||||
|
"""
|
||||||
|
based on walk naive, but with a head and a tail
|
||||||
|
"""
|
||||||
slider_max = 0.200
|
slider_max = 0.200
|
||||||
|
|
||||||
real_position = np.copy(neutral_position)
|
real_position = np.copy(neutral_position)
|
||||||
@ -420,7 +503,7 @@ def dino_naive(t, speed_x, speed_y, hz, hy, hx):
|
|||||||
real_position[5][2] = 0.05 + hz
|
real_position[5][2] = 0.05 + hz
|
||||||
real_position[5][0] = 0.25 + hx
|
real_position[5][0] = 0.25 + hx
|
||||||
real_position[5][1] = hy
|
real_position[5][1] = hy
|
||||||
print(hx)
|
|
||||||
return legs(real_position)
|
return legs(real_position)
|
||||||
|
|
||||||
|
|
||||||
|
20
simulator.py
20
simulator.py
@ -3,6 +3,7 @@ import argparse
|
|||||||
import math
|
import math
|
||||||
import time
|
import time
|
||||||
import pybullet as p
|
import pybullet as p
|
||||||
|
|
||||||
if __package__ is None or __package__ == '':
|
if __package__ is None or __package__ == '':
|
||||||
import control
|
import control
|
||||||
else:
|
else:
|
||||||
@ -14,6 +15,7 @@ dirname = os.path.dirname(__file__) + '/models/'
|
|||||||
n_motors = 0
|
n_motors = 0
|
||||||
jointsMap = []
|
jointsMap = []
|
||||||
|
|
||||||
|
|
||||||
def init():
|
def init():
|
||||||
"""Initialise le simulateur"""
|
"""Initialise le simulateur"""
|
||||||
# Instanciation de Bullet
|
# Instanciation de Bullet
|
||||||
@ -60,6 +62,7 @@ def inverseControls(name='', x_default=0.15, y_default=0.):
|
|||||||
|
|
||||||
return target_x, target_y, target_z, target
|
return target_x, target_y, target_z, target
|
||||||
|
|
||||||
|
|
||||||
def directControls():
|
def directControls():
|
||||||
alpha = p.addUserDebugParameter('alpha', -math.pi, math.pi, 0)
|
alpha = p.addUserDebugParameter('alpha', -math.pi, math.pi, 0)
|
||||||
beta = p.addUserDebugParameter('beta', -math.pi, math.pi, 0)
|
beta = p.addUserDebugParameter('beta', -math.pi, math.pi, 0)
|
||||||
@ -78,6 +81,7 @@ def inverseUpdate(controls):
|
|||||||
|
|
||||||
return x, y, z
|
return x, y, z
|
||||||
|
|
||||||
|
|
||||||
def tick():
|
def tick():
|
||||||
global t
|
global t
|
||||||
|
|
||||||
@ -85,6 +89,7 @@ def tick():
|
|||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
time.sleep(dt)
|
time.sleep(dt)
|
||||||
|
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
# Arguments
|
# Arguments
|
||||||
parser = argparse.ArgumentParser(prog="Quadruped")
|
parser = argparse.ArgumentParser(prog="Quadruped")
|
||||||
@ -161,6 +166,8 @@ if __name__ == "__main__":
|
|||||||
|
|
||||||
robot = loadModel(robot, fixed, startPos, startOrientation)
|
robot = loadModel(robot, fixed, startPos, startOrientation)
|
||||||
|
|
||||||
|
target = loadModel('target2', True)
|
||||||
|
|
||||||
# Boucle principale
|
# Boucle principale
|
||||||
while True:
|
while True:
|
||||||
if mode == 'motors':
|
if mode == 'motors':
|
||||||
@ -181,10 +188,12 @@ if __name__ == "__main__":
|
|||||||
elif mode == 'draw':
|
elif mode == 'draw':
|
||||||
joints = control.draw(t) + [0] * (n_motors - 3)
|
joints = control.draw(t) + [0] * (n_motors - 3)
|
||||||
|
|
||||||
|
|
||||||
def getLegTip():
|
def getLegTip():
|
||||||
res = p.getLinkState(robot, 3)
|
res = p.getLinkState(robot, 3)
|
||||||
return res[0]
|
return res[0]
|
||||||
|
|
||||||
|
|
||||||
if lastLine is None:
|
if lastLine is None:
|
||||||
lastLine = time.time(), getLegTip()
|
lastLine = time.time(), getLegTip()
|
||||||
elif time.time() - lastLine[0] > 0.1:
|
elif time.time() - lastLine[0] > 0.1:
|
||||||
@ -201,7 +210,16 @@ if __name__ == "__main__":
|
|||||||
x = p.readUserDebugParameter(speed_x)
|
x = p.readUserDebugParameter(speed_x)
|
||||||
y = p.readUserDebugParameter(speed_y)
|
y = p.readUserDebugParameter(speed_y)
|
||||||
rotation = p.readUserDebugParameter(speed_rotation)
|
rotation = p.readUserDebugParameter(speed_rotation)
|
||||||
joints = control.walk(t, x, y, rotation)
|
data = control.walk(t, x, y, rotation)
|
||||||
|
if len(data) == 2: # When we receive the position of a target
|
||||||
|
joints = data[0]
|
||||||
|
x, y = data[1]
|
||||||
|
z = 0
|
||||||
|
else:
|
||||||
|
joints = data
|
||||||
|
x, y, z = 0, 0, -5 # We hide the target under the map
|
||||||
|
p.resetBasePositionAndOrientation(target, [x, y, z],
|
||||||
|
p.getQuaternionFromEuler([0, 0, 0]))
|
||||||
elif mode == 'sandbox':
|
elif mode == 'sandbox':
|
||||||
joints = control.sandbox(t)
|
joints = control.sandbox(t)
|
||||||
|
|
||||||
|
8
xbox.py
8
xbox.py
@ -15,9 +15,9 @@ class Xbox:
|
|||||||
|
|
||||||
if len(self.controllers) == 0:
|
if len(self.controllers) == 0:
|
||||||
self.logger.critical("No controllers detected. Can't initialize remote control.")
|
self.logger.critical("No controllers detected. Can't initialize remote control.")
|
||||||
self.initialized = True
|
|
||||||
else:
|
|
||||||
self.initialized = False
|
self.initialized = False
|
||||||
|
else:
|
||||||
|
self.initialized = True
|
||||||
self.data = {"x1": 0, "x2": 0, "y1": 0, "y2": 0, "up": 0, "down": 0, "left": 0, "right": 0, "r1": 0, "r2": 0,
|
self.data = {"x1": 0, "x2": 0, "y1": 0, "y2": 0, "up": 0, "down": 0, "left": 0, "right": 0, "r1": 0, "r2": 0,
|
||||||
"r3": 0,
|
"r3": 0,
|
||||||
"l1": 0, "l2": 0, "l3": 0}
|
"l1": 0, "l2": 0, "l3": 0}
|
||||||
@ -31,12 +31,12 @@ class Xbox:
|
|||||||
axis = event["axis"]
|
axis = event["axis"]
|
||||||
if axis in [1, 4]:
|
if axis in [1, 4]:
|
||||||
value = -event["value"]
|
value = -event["value"]
|
||||||
if abs(value) < 0.1:
|
if abs(value) < 0.2:
|
||||||
value = 0
|
value = 0
|
||||||
self.data[{0: "x1", 1: "y1", 4: "y2", 3: "x2", 5: "r2", 2: "l2"}[event["axis"]]] = value
|
self.data[{0: "x1", 1: "y1", 4: "y2", 3: "x2", 5: "r2", 2: "l2"}[event["axis"]]] = value
|
||||||
else:
|
else:
|
||||||
value = event["value"]
|
value = event["value"]
|
||||||
if abs(value) < 0.1:
|
if abs(value) < 0.2:
|
||||||
value = 0
|
value = 0
|
||||||
self.data[{0: "x1", 1: "y1", 4: "y2", 3: "x2", 5: "r2", 2: "l2"}[event["axis"]]] = value
|
self.data[{0: "x1", 1: "y1", 4: "y2", 3: "x2", 5: "r2", 2: "l2"}[event["axis"]]] = value
|
||||||
elif "button" in keys:
|
elif "button" in keys:
|
||||||
|
Reference in New Issue
Block a user