talos_arm_conf.py
Go to the documentation of this file.
1 from pathlib import Path
2 
3 import numpy as np
4 from example_robot_data.robots_loader import getModelPath
5 
6 np.set_printoptions(precision=3, linewidth=200, suppress=True)
7 LINE_WIDTH = 60
8 
9 N_SIMULATION = 4000 # number of time steps simulated
10 dt = 0.002 # controller time step
11 q0 = np.array([1.73046e-01, -2e-04, -5.25366e-01, 0, 0, 1, 0])
12 
13 # REFERENCE SINUSOIDAL TRAJECTORY
14 amp = np.array([0 * 0.02, 0.1, 0.10]) # amplitude
15 phi = np.array([0.0, 0.5 * np.pi, 0.0]) # phase
16 two_pi_f = 1.4 * 2 * np.pi * np.array([1.0, 0.5, 0.5]) # frequency (time 2 PI)
17 offset = np.array([0.0, 0.0, 0.0])
18 
19 w_ee = 1.0 # weight of end-effector task
20 w_posture = 1e-3 # weight of joint posture task
21 w_torque_bounds = 1.0 # weight of the torque bounds
22 w_joint_bounds = 1.0
23 
24 kp_ee = 5.0 # proportional gain of end-effector constraint
25 kp_posture = 1.0 # proportional gain of joint posture task
26 
27 tau_max_scaling = 0.4 # scaling factor of torque bounds
28 v_max_scaling = 0.4
29 
30 ee_frame_name = "ee_fixed_joint" # end-effector frame name
31 ee_task_mask = np.array([1.0, 1, 1, 0, 0, 0])
32 
33 PRINT_N = 500 # print every PRINT_N time steps
34 DISPLAY_N = 20 # update robot configuration in viwewer every DISPLAY_N time steps
35 CAMERA_TRANSFORM = [
36  2.582354784011841,
37  1.620774507522583,
38  1.0674564838409424,
39  0.2770655155181885,
40  0.5401807427406311,
41  0.6969326734542847,
42  0.3817386031150818,
43 ]
44 SPHERE_RADIUS = 0.03
45 REF_SPHERE_RADIUS = 0.03
46 EE_SPHERE_COLOR = (1, 0.5, 0, 0.5)
47 EE_REF_SPHERE_COLOR = (1, 0, 0, 0.5)
48 
49 urdf = "/talos_data/robots/talos_left_arm.urdf"
50 path = Path(getModelPath(urdf))
51 urdf = path / urdf
example_robot_data::robots_loader


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sat May 3 2025 02:48:17