1
1
disableImplicitNetworkWrapper
2
2
yarpDeviceName left_hand_hardware_device
3
- jointNames l_thumb_add l_thumb_prox l_thumb_dist l_index_add l_index_prox l_index_dist l_middle_prox l_middle_dist l_ring_prox l_ring_dist l_pinkie_prox l_pinkie_dist
4
- max_torques 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0
3
+ jointNames ( l_thumb_add l_thumb_prox l_thumb_dist l_index_add l_index_prox l_index_dist l_middle_prox l_middle_dist l_ring_prox l_ring_dist l_pinkie_prox l_pinkie_dist)
4
+ max_torques ( 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0)
5
5
6
6
[COUPLING]
7
7
device couplingXCubHandMk5
8
- actuatedAxesNames l_thumb_add l_thumb_oc l_index_add l_index_oc l_middle_oc l_ring_pinky_oc
9
- actuatedAxesPosMin 0.0 0.0 0.0 0.0 0.0 0.0
10
- actuatedAxesPosMax 90.0 82.1 15.0 90.0 90.0 90.0
8
+ actuatedAxesNames ( l_thumb_add l_thumb_oc l_index_add l_index_oc l_middle_oc l_ring_pinky_oc)
9
+ actuatedAxesPosMin ( 0.0 0.0 0.0 0.0 0.0 0.0)
10
+ actuatedAxesPosMax ( 90.0 82.1 15.0 90.0 90.0 90.0)
11
11
12
12
[COUPLING_PARAMS]
13
- L0x -0.00555 -0.0050 -0.0050 -0.0050 -0.0050
14
- L0y 0.00285 0.0040 0.0040 0.0040 0.0040
15
- q2bias -180.0 -173.35 -173.35 -173.35 -170.54
16
- q1off 4.29 2.86 2.86 2.86 3.43
17
- k 0.0171 0.02918 0.02918 0.02918 0.02425
18
- d 0.02006 0.03004 0.03004 0.03004 0.02504
19
- l 0.0085 0.00604 0.00604 0.00604 0.00608
20
- b 0.00624 0.0064 0.0064 0.0064 0.0064
13
+ L0x ( -0.00555 -0.0050 -0.0050 -0.0050 -0.0050)
14
+ L0y ( 0.00285 0.0040 0.0040 0.0040 0.0040)
15
+ q2bias ( -180.0 -173.35 -173.35 -173.35 -170.54)
16
+ q1off ( 4.29 2.86 2.86 2.86 3.43)
17
+ k ( 0.0171 0.02918 0.02918 0.02918 0.02425)
18
+ d ( 0.02006 0.03004 0.03004 0.03004 0.02504)
19
+ l ( 0.0085 0.00604 0.00604 0.00604 0.00608)
20
+ b ( 0.00624 0.0064 0.0064 0.0064 0.0064)
21
21
22
22
[TRAJECTORY_GENERATION]
23
23
trajectory_type minimum_jerk
24
24
25
25
[LIMITS]
26
- jntVelMax 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0
27
- jntPosMax 90.0 82.1 53.6 15.0 90.0 99.2 90.0 99.2 90.0 99.2 90.0 93.3
28
- jntPosMin 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0
26
+ jntVelMax ( 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0 100.0)
27
+ jntPosMax ( 90.0 82.1 53.6 15.0 90.0 99.2 90.0 99.2 90.0 99.2 90.0 93.3)
28
+ jntPosMin ( 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0)
29
29
30
30
[POSITION_CONTROL]
31
31
controlUnits metric_units
32
32
controlLaw joint_pid_gazebo_v1
33
- kp 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0
34
- kd 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0
35
- ki 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00
36
- maxInt 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999
37
- maxOutput 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999
38
- shift 0 0 0 0 0 0 0 0 0 0 0 0
39
- ko 0 0 0 0 0 0 0 0 0 0 0 0
40
- stictionUp 0 0 0 0 0 0 0 0 0 0 0 0
41
- stictionDwn 0 0 0 0 0 0 0 0 0 0 0 0
33
+ kp ( 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0 5.0)
34
+ kd ( 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0)
35
+ ki ( 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00 0.00)
36
+ maxInt ( 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999)
37
+ maxOutput ( 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999)
38
+ shift ( 0 0 0 0 0 0 0 0 0 0 0 0)
39
+ ko ( 0 0 0 0 0 0 0 0 0 0 0 0)
40
+ stictionUp ( 0 0 0 0 0 0 0 0 0 0 0 0)
41
+ stictionDwn ( 0 0 0 0 0 0 0 0 0 0 0 0)
42
42
43
43
[VELOCITY_CONTROL]
44
44
controlUnits metric_units
45
45
controlLaw joint_pid_gazebo_v1
46
46
velocityControlImplementationType integrator_and_position_pid
47
- kp 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01
48
- kd 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0
49
- ki 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0
50
- maxInt 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999
51
- maxOutput 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999
52
- shift 0 0 0 0 0 0 0 0 0 0 0 0
53
- ko 0 0 0 0 0 0 0 0 0 0 0 0
54
- stictionUp 0 0 0 0 0 0 0 0 0 0 0 0
55
- stictionDwn 0 0 0 0 0 0 0 0 0 0 0 0
47
+ kp ( 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01 0.01)
48
+ kd ( 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0)
49
+ ki ( 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0)
50
+ maxInt ( 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999)
51
+ maxOutput ( 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999 9999)
52
+ shift ( 0 0 0 0 0 0 0 0 0 0 0 0)
53
+ ko ( 0 0 0 0 0 0 0 0 0 0 0 0)
54
+ stictionUp ( 0 0 0 0 0 0 0 0 0 0 0 0)
55
+ stictionDwn ( 0 0 0 0 0 0 0 0 0 0 0 0)
56
56
57
57
[IMPEDANCE_CONTROL]
58
58
controlUnits metric_units
59
59
controlLaw joint_pid_gazebo_v1
60
- stiffness 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0
61
- damping 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0
60
+ stiffness ( 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0)
61
+ damping ( 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0)
0 commit comments