Variables | |
| int | alpha = 10 ** (2) |
| int | beta = 0 |
| list | CAMERA_TRANSFORM |
| contactNormal | |
| string | DATA_FILE_LIPM = "romeo_walking_traj_lipm.npz" |
| string | DATA_FILE_TSID = "romeo_walking_traj_tsid.npz" |
| int | DISPLAY_N = 20 |
| float | dt = 0.002 |
| float | dt_mpc = 0.1 |
| filename = str(os.path.dirname(os.path.abspath(__file__))) | |
| int | fMax = 1e6 |
| float | fMin = 0.0 |
| float | foot_scaling = 1.0 |
| foot_step_0 = np.array([0.0, -0.096]) | |
| float | g = 9.81 |
| float | gain_vector = kp_posture * np.ones(nv - 6) |
| int | gamma = 10 ** (-1) |
| float | h = 0.58 |
| float | kp_am = 10.0 |
| float | kp_com = 10.0 |
| float | kp_contact = 10.0 |
| float | kp_foot = 10.0 |
| float | kp_posture = 1.0 |
| string | lf_frame_name = "LAnkleRoll" |
| int | LINE_WIDTH = 60 |
| linewidth | |
| float | lxn = foot_scaling * 0.05 |
| float | lxp = foot_scaling * 0.10 |
| float | lyn = foot_scaling * 0.05 |
| float | lyp = foot_scaling * 0.05 |
| float | lz = 0.07 |
| masks_posture = np.ones(nv - 6) | |
| float | mu = 0.3 |
| int | nb_steps = 4 |
| int | nv = 37 |
| string | path = filename + "/../models/romeo" |
| precision | |
| int | PRINT_N = 500 |
| string | rf_frame_name = "RAnkleRoll" |
| string | srdf = path + "/srdf/romeo_collision.srdf" |
| float | step_height = 0.05 |
| float | step_length = 0.05 |
| suppress | |
| float | T_post = 1.5 |
| float | T_pre = 1.5 |
| float | T_step = 1.2 |
| float | tau_max_scaling = 1.45 |
| string | urdf = path + "/urdf/romeo.urdf" |
| float | v_max_scaling = 0.8 |
| viewer = pin.visualize.GepettoVisualizer | |
| int | w_am = 1e-4 |
| float | w_com = 1.0 |
| int | w_contact = 1e2 |
| float | w_cop = 0.0 |
| int | w_foot = 1e0 |
| int | w_forceRef = 1e-5 |
| float | w_joint_bounds = 0.0 |
| int | w_posture = 1e-4 |
| float | w_torque_bounds = 0.0 |
| int ex_4_conf.alpha = 10 ** (2) |
Definition at line 43 of file ex_4_conf.py.
| int ex_4_conf.beta = 0 |
Definition at line 44 of file ex_4_conf.py.
| list ex_4_conf.CAMERA_TRANSFORM |
Definition at line 87 of file ex_4_conf.py.
| ex_4_conf.contactNormal |
Definition at line 37 of file ex_4_conf.py.
| string ex_4_conf.DATA_FILE_LIPM = "romeo_walking_traj_lipm.npz" |
Definition at line 16 of file ex_4_conf.py.
| string ex_4_conf.DATA_FILE_TSID = "romeo_walking_traj_tsid.npz" |
Definition at line 17 of file ex_4_conf.py.
| int ex_4_conf.DISPLAY_N = 20 |
Definition at line 86 of file ex_4_conf.py.
| float ex_4_conf.dt = 0.002 |
Definition at line 57 of file ex_4_conf.py.
| float ex_4_conf.dt_mpc = 0.1 |
Definition at line 49 of file ex_4_conf.py.
| ex_4_conf.filename = str(os.path.dirname(os.path.abspath(__file__))) |
Definition at line 21 of file ex_4_conf.py.
| int ex_4_conf.fMax = 1e6 |
Definition at line 34 of file ex_4_conf.py.
| float ex_4_conf.fMin = 0.0 |
Definition at line 33 of file ex_4_conf.py.
| float ex_4_conf.foot_scaling = 1.0 |
Definition at line 26 of file ex_4_conf.py.
| ex_4_conf.foot_step_0 = np.array([0.0, -0.096]) |
Definition at line 48 of file ex_4_conf.py.
| float ex_4_conf.g = 9.81 |
Definition at line 47 of file ex_4_conf.py.
| float ex_4_conf.gain_vector = kp_posture * np.ones(nv - 6) |
Definition at line 79 of file ex_4_conf.py.
| int ex_4_conf.gamma = 10 ** (-1) |
Definition at line 45 of file ex_4_conf.py.
| float ex_4_conf.h = 0.58 |
Definition at line 46 of file ex_4_conf.py.
| float ex_4_conf.kp_am = 10.0 |
Definition at line 77 of file ex_4_conf.py.
| float ex_4_conf.kp_com = 10.0 |
Definition at line 76 of file ex_4_conf.py.
| float ex_4_conf.kp_contact = 10.0 |
Definition at line 74 of file ex_4_conf.py.
| float ex_4_conf.kp_foot = 10.0 |
Definition at line 75 of file ex_4_conf.py.
| float ex_4_conf.kp_posture = 1.0 |
Definition at line 78 of file ex_4_conf.py.
| string ex_4_conf.lf_frame_name = "LAnkleRoll" |
Definition at line 36 of file ex_4_conf.py.
| int ex_4_conf.LINE_WIDTH = 60 |
Definition at line 14 of file ex_4_conf.py.
| ex_4_conf.linewidth |
Definition at line 13 of file ex_4_conf.py.
| float ex_4_conf.lxn = foot_scaling * 0.05 |
Definition at line 28 of file ex_4_conf.py.
| float ex_4_conf.lxp = foot_scaling * 0.10 |
Definition at line 27 of file ex_4_conf.py.
| float ex_4_conf.lyn = foot_scaling * 0.05 |
Definition at line 30 of file ex_4_conf.py.
| float ex_4_conf.lyp = foot_scaling * 0.05 |
Definition at line 29 of file ex_4_conf.py.
| float ex_4_conf.lz = 0.07 |
Definition at line 31 of file ex_4_conf.py.
Definition at line 80 of file ex_4_conf.py.
| float ex_4_conf.mu = 0.3 |
Definition at line 32 of file ex_4_conf.py.
| int ex_4_conf.nb_steps = 4 |
Definition at line 53 of file ex_4_conf.py.
| int ex_4_conf.nv = 37 |
Definition at line 25 of file ex_4_conf.py.
| string ex_4_conf.path = filename + "/../models/romeo" |
Definition at line 22 of file ex_4_conf.py.
| ex_4_conf.precision |
Definition at line 13 of file ex_4_conf.py.
| int ex_4_conf.PRINT_N = 500 |
Definition at line 85 of file ex_4_conf.py.
| string ex_4_conf.rf_frame_name = "RAnkleRoll" |
Definition at line 35 of file ex_4_conf.py.
| string ex_4_conf.srdf = path + "/srdf/romeo_collision.srdf" |
Definition at line 24 of file ex_4_conf.py.
| float ex_4_conf.step_height = 0.05 |
Definition at line 52 of file ex_4_conf.py.
| float ex_4_conf.step_length = 0.05 |
Definition at line 51 of file ex_4_conf.py.
| ex_4_conf.suppress |
Definition at line 13 of file ex_4_conf.py.
| float ex_4_conf.T_post = 1.5 |
Definition at line 59 of file ex_4_conf.py.
| float ex_4_conf.T_pre = 1.5 |
Definition at line 58 of file ex_4_conf.py.
| float ex_4_conf.T_step = 1.2 |
Definition at line 50 of file ex_4_conf.py.
| float ex_4_conf.tau_max_scaling = 1.45 |
Definition at line 71 of file ex_4_conf.py.
| string ex_4_conf.urdf = path + "/urdf/romeo.urdf" |
Definition at line 23 of file ex_4_conf.py.
| float ex_4_conf.v_max_scaling = 0.8 |
Definition at line 72 of file ex_4_conf.py.
| ex_4_conf.viewer = pin.visualize.GepettoVisualizer |
Definition at line 84 of file ex_4_conf.py.
| int ex_4_conf.w_am = 1e-4 |
Definition at line 63 of file ex_4_conf.py.
| float ex_4_conf.w_com = 1.0 |
Definition at line 61 of file ex_4_conf.py.
| int ex_4_conf.w_contact = 1e2 |
Definition at line 65 of file ex_4_conf.py.
| float ex_4_conf.w_cop = 0.0 |
Definition at line 62 of file ex_4_conf.py.
| int ex_4_conf.w_foot = 1e0 |
Definition at line 64 of file ex_4_conf.py.
| int ex_4_conf.w_forceRef = 1e-5 |
Definition at line 67 of file ex_4_conf.py.
| float ex_4_conf.w_joint_bounds = 0.0 |
Definition at line 69 of file ex_4_conf.py.
| int ex_4_conf.w_posture = 1e-4 |
Definition at line 66 of file ex_4_conf.py.
| float ex_4_conf.w_torque_bounds = 0.0 |
Definition at line 68 of file ex_4_conf.py.