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


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Sun Jul 2 2023 02:21:51