1 from pathlib
import Path
4 import pinocchio
as pin
7 np.set_printoptions(precision=3, linewidth=200, suppress=
True)
21 rf_frame_name =
"leg_right_sole_fix_joint"
22 lf_frame_name =
"leg_left_sole_fix_joint"
23 contactNormal = np.array(
37 gain_vector = np.array(
73 masks_posture = np.ones(32)
75 tau_max_scaling = 1.45
84 viewer = pin.visualize.GepettoVisualizer
98 REF_SPHERE_RADIUS = 0.03
99 COM_SPHERE_COLOR = (1, 0.5, 0, 0.5)
100 COM_REF_SPHERE_COLOR = (1, 0, 0, 0.5)
101 RF_SPHERE_COLOR = (0, 1, 0, 0.5)
102 RF_REF_SPHERE_COLOR = (0, 1, 0.5, 0.5)
103 LF_SPHERE_COLOR = (0, 0, 1, 0.5)
104 LF_REF_SPHERE_COLOR = (0.5, 0, 1, 0.5)
106 urdf =
"/talos_data/robots/talos_reduced.urdf"
107 path = Path(getModelPath(urdf))
109 srdf = path /
"talos_data/srdf/talos.srdf"
110 path = path /
"../.."