Variables | |
alpha | |
ax | |
com_acc = np.empty((3, N + N_post)) * nan | |
tuple | com_acc_des |
com_acc_ref = np.asarray(data["ddcom"]) | |
com_pos = np.empty((3, N + N_post)) * nan | |
com_pos_ref = np.asarray(data["com"]) | |
com_vel = np.empty((3, N + N_post)) * nan | |
com_vel_ref = np.asarray(data["dcom"]) | |
contact_phase = data["contact_phase"] | |
cop = np.zeros((2, N + N_post)) | |
cop_LF = np.zeros((2, N + N_post)) | |
cop_LF_world | |
cop_ref = np.asarray(data["cop"]) | |
cop_RF = np.zeros((2, N + N_post)) | |
cop_RF_world | |
data = np.load(conf.DATA_FILE_TSID) | |
ddx_LF = np.empty((3, N + N_post)) * nan | |
ddx_LF_des = np.empty((3, N + N_post)) * nan | |
ddx_LF_ref = np.asarray(data["ddx_LF"]) | |
ddx_RF = np.empty((3, N + N_post)) * nan | |
ddx_RF_des = np.empty((3, N + N_post)) * nan | |
ddx_RF_ref = np.asarray(data["ddx_RF"]) | |
dv = tsid.formulation.getAccelerations(sol) | |
dx_LF = np.empty((3, N + N_post)) * nan | |
dx_LF_ref = np.asarray(data["dx_LF"]) | |
dx_RF = np.empty((3, N + N_post)) * nan | |
dx_RF_ref = np.asarray(data["dx_RF"]) | |
f | |
f_LF = np.zeros((6, N + N_post)) | |
f_RF = np.zeros((6, N + N_post)) | |
HQPData = tsid.formulation.computeProblemData(t, q, v) | |
label | |
leg = ax[i].legend() | |
N = data["com"].shape[1] | |
N_post = int(conf.T_post / conf.dt) | |
N_pre = int(conf.T_pre / conf.dt) | |
offset = x_rf - x_RF_ref[:, 0] | |
int | PLOT_COM = 0 |
int | PLOT_COP = 1 |
int | PLOT_FOOT_TRAJ = 0 |
int | PLOT_JOINT_VEL = 0 |
int | PLOT_TORQUES = 0 |
q | |
q_log = np.zeros((tsid.robot.nq, N + N_post)) | |
sol = tsid.solver.solve(HQPData) | |
t = -conf.T_pre | |
T_LF = tsid.contactRF.getForceGeneratorMatrix | |
T_RF = tsid.contactRF.getForceGeneratorMatrix | |
tau = np.zeros((tsid.robot.na, N + N_post)) | |
tuple | tau_normalized |
time = np.arange(0.0, (N + N_post) * conf.dt, conf.dt) | |
time_spent = time.time() - time_start | |
time_start = time.time() | |
tsid = TsidBiped(conf, conf.viewer) | |
v | |
v_log = np.zeros((tsid.robot.nv, N + N_post)) | |
tuple | v_normalized |
x_LF = np.empty((3, N + N_post)) * nan | |
x_LF_ref = np.asarray(data["x_LF"]) | |
x_RF = np.empty((3, N + N_post)) * nan | |
x_rf = tsid.get_placement_RF().translation | |
x_RF_ref = np.asarray(data["x_RF"]) | |
This script is a slight variation of ex_4_walking.py introduced to test the new center of pressure (CoP) task. In this script, besides tracking a reference center of mass (CoM), the TSID controller also tries to track a reference CoP. The resulting motion doesn't look great because the reference CoP is an open-loop reference trajectory, so it is not stabilizing, and it conflicts with the CoM task. However, the results show that the CoP is tracked reasonably well during the motion, which was the goal of the test, validating the CoP task.
test_cop_task.alpha |
Definition at line 333 of file test_cop_task.py.
test_cop_task.ax |
Definition at line 215 of file test_cop_task.py.
Definition at line 42 of file test_cop_task.py.
tuple test_cop_task.com_acc_des |
Definition at line 71 of file test_cop_task.py.
test_cop_task.com_acc_ref = np.asarray(data["ddcom"]) |
Definition at line 63 of file test_cop_task.py.
Definition at line 40 of file test_cop_task.py.
test_cop_task.com_pos_ref = np.asarray(data["com"]) |
Definition at line 61 of file test_cop_task.py.
Definition at line 41 of file test_cop_task.py.
test_cop_task.com_vel_ref = np.asarray(data["dcom"]) |
Definition at line 62 of file test_cop_task.py.
test_cop_task.contact_phase = data["contact_phase"] |
Definition at line 60 of file test_cop_task.py.
Definition at line 55 of file test_cop_task.py.
Definition at line 54 of file test_cop_task.py.
test_cop_task.cop_LF_world |
Definition at line 168 of file test_cop_task.py.
test_cop_task.cop_ref = np.asarray(data["cop"]) |
Definition at line 70 of file test_cop_task.py.
Definition at line 53 of file test_cop_task.py.
test_cop_task.cop_RF_world |
Definition at line 171 of file test_cop_task.py.
test_cop_task.data = np.load(conf.DATA_FILE_TSID) |
Definition at line 32 of file test_cop_task.py.
Definition at line 45 of file test_cop_task.py.
Definition at line 46 of file test_cop_task.py.
test_cop_task.ddx_LF_ref = np.asarray(data["ddx_LF"]) |
Definition at line 69 of file test_cop_task.py.
Definition at line 49 of file test_cop_task.py.
Definition at line 50 of file test_cop_task.py.
test_cop_task.ddx_RF_ref = np.asarray(data["ddx_RF"]) |
Definition at line 66 of file test_cop_task.py.
test_cop_task.dv = tsid.formulation.getAccelerations(sol) |
Definition at line 138 of file test_cop_task.py.
Definition at line 44 of file test_cop_task.py.
test_cop_task.dx_LF_ref = np.asarray(data["dx_LF"]) |
Definition at line 68 of file test_cop_task.py.
Definition at line 48 of file test_cop_task.py.
test_cop_task.dx_RF_ref = np.asarray(data["dx_RF"]) |
Definition at line 65 of file test_cop_task.py.
test_cop_task.f |
Definition at line 215 of file test_cop_task.py.
Definition at line 52 of file test_cop_task.py.
Definition at line 51 of file test_cop_task.py.
Definition at line 124 of file test_cop_task.py.
test_cop_task.label |
Definition at line 217 of file test_cop_task.py.
Definition at line 221 of file test_cop_task.py.
test_cop_task.N = data["com"].shape[1] |
Definition at line 36 of file test_cop_task.py.
test_cop_task.N_post = int(conf.T_post / conf.dt) |
Definition at line 38 of file test_cop_task.py.
test_cop_task.N_pre = int(conf.T_pre / conf.dt) |
Definition at line 37 of file test_cop_task.py.
Definition at line 76 of file test_cop_task.py.
int test_cop_task.PLOT_COM = 0 |
Definition at line 26 of file test_cop_task.py.
int test_cop_task.PLOT_COP = 1 |
Definition at line 27 of file test_cop_task.py.
int test_cop_task.PLOT_FOOT_TRAJ = 0 |
Definition at line 28 of file test_cop_task.py.
int test_cop_task.PLOT_JOINT_VEL = 0 |
Definition at line 30 of file test_cop_task.py.
int test_cop_task.PLOT_TORQUES = 0 |
Definition at line 29 of file test_cop_task.py.
test_cop_task.q |
Definition at line 86 of file test_cop_task.py.
test_cop_task.q_log = np.zeros((tsid.robot.nq, N + N_post)) |
Definition at line 57 of file test_cop_task.py.
test_cop_task.sol = tsid.solver.solve(HQPData) |
Definition at line 126 of file test_cop_task.py.
test_cop_task.t = -conf.T_pre |
Definition at line 85 of file test_cop_task.py.
test_cop_task.T_LF = tsid.contactRF.getForceGeneratorMatrix |
Definition at line 161 of file test_cop_task.py.
test_cop_task.T_RF = tsid.contactRF.getForceGeneratorMatrix |
Definition at line 153 of file test_cop_task.py.
Definition at line 56 of file test_cop_task.py.
test_cop_task.tau_normalized |
Definition at line 328 of file test_cop_task.py.
Definition at line 212 of file test_cop_task.py.
test_cop_task.time_spent = time.time() - time_start |
Definition at line 207 of file test_cop_task.py.
test_cop_task.time_start = time.time() |
Definition at line 89 of file test_cop_task.py.
test_cop_task.tsid = TsidBiped(conf, conf.viewer) |
Definition at line 34 of file test_cop_task.py.
test_cop_task.v |
Definition at line 86 of file test_cop_task.py.
test_cop_task.v_log = np.zeros((tsid.robot.nv, N + N_post)) |
Definition at line 58 of file test_cop_task.py.
test_cop_task.v_normalized |
Definition at line 344 of file test_cop_task.py.
Definition at line 43 of file test_cop_task.py.
test_cop_task.x_LF_ref = np.asarray(data["x_LF"]) |
Definition at line 67 of file test_cop_task.py.
Definition at line 47 of file test_cop_task.py.
test_cop_task.x_rf = tsid.get_placement_RF().translation |
Definition at line 75 of file test_cop_task.py.
test_cop_task.x_RF_ref = np.asarray(data["x_RF"]) |
Definition at line 64 of file test_cop_task.py.