Skip to content

Commit aab86dc

Browse files
committed
Port all ini to use parenthesis
1 parent 9f2cb89 commit aab86dc

10 files changed

+291
-291
lines changed
+29-29
Original file line numberDiff line numberDiff line change
@@ -1,51 +1,51 @@
11
disableImplicitNetworkWrapper
22
yarpDeviceName head_hardware_device
33

4-
jointNames neck_pitch neck_roll neck_yaw camera_tilt
4+
jointNames (neck_pitch neck_roll neck_yaw camera_tilt)
55

6-
min_stiffness 0.0 0.0 0.0 0.0
7-
max_stiffness 1000.0 1000.0 1000.0 1000.0
8-
min_damping 0.0 0.0 0.0 0.0
9-
max_damping 100.0 100.0 100.0 100.0
10-
max_torques 1000000.0 1000000.0 1000000.0 1000000.0
6+
min_stiffness (0.0 0.0 0.0 0.0)
7+
max_stiffness (1000.0 1000.0 1000.0 1000.0)
8+
min_damping (0.0 0.0 0.0 0.0)
9+
max_damping (100.0 100.0 100.0 100.0)
10+
max_torques (1000000.0 1000000.0 1000000.0 1000000.0)
1111

1212

1313
#PIDs:
1414
# this information is used to set the PID values in simulation for GAZEBO, we need only the first three values
1515
[POSITION_CONTROL]
1616
controlUnits metric_units
1717
controlLaw joint_pid_gazebo_v1
18-
kp 1.745 1.745 1.745 1.745
19-
kd 0.122 0.122 0.122 0.122
20-
ki 0.003 0.003 0.003 0.003
21-
maxInt 9999 9999 9999 9999
22-
maxOutput 9999 9999 9999 9999
23-
shift 0.0 0.0 0.0 0.0
24-
ko 0.0 0.0 0.0 0.0
25-
stictionUp 0.0 0.0 0.0 0.0
26-
stictionDwn 0.0 0.0 0.0 0.0
18+
kp (1.745 1.745 1.745 1.745)
19+
kd (0.122 0.122 0.122 0.122)
20+
ki (0.003 0.003 0.003 0.003)
21+
maxInt (9999 9999 9999 9999)
22+
maxOutput (9999 9999 9999 9999)
23+
shift (0.0 0.0 0.0 0.0)
24+
ko (0.0 0.0 0.0 0.0)
25+
stictionUp (0.0 0.0 0.0 0.0)
26+
stictionDwn (0.0 0.0 0.0 0.0)
2727

2828
[VELOCITY_CONTROL]
2929
velocityControlImplementationType integrator_and_position_pid
3030
controlUnits metric_units
3131
controlLaw joint_pid_gazebo_v1
32-
kp 8.726 8.726 8.726 8.726
33-
kd 0.035 0.035 0.035 0.035
34-
ki 0.003 0.003 0.003 0.003
35-
maxInt 9999 9999 9999 9999
36-
maxOutput 9999 9999 9999 9999
37-
shift 0.0 0.0 0.0 0.0
38-
ko 0.0 0.0 0.0 0.0
39-
stictionUp 0.0 0.0 0.0 0.0
40-
stictionDwn 0.0 0.0 0.0 0.0
32+
kp (8.726 8.726 8.726 8.726)
33+
kd (0.035 0.035 0.035 0.035)
34+
ki (0.003 0.003 0.003 0.003)
35+
maxInt (9999 9999 9999 9999)
36+
maxOutput (9999 9999 9999 9999)
37+
shift (0.0 0.0 0.0 0.0)
38+
ko (0.0 0.0 0.0 0.0)
39+
stictionUp (0.0 0.0 0.0 0.0)
40+
stictionDwn (0.0 0.0 0.0 0.0)
4141

4242
[IMPEDANCE_CONTROL]
4343
controlUnits metric_units
4444
controlLaw joint_pid_gazebo_v1
45-
stiffness 0.0 0.0 0.0 0.0
46-
damping 0.0 0.0 0.0 0.0
45+
stiffness (0.0 0.0 0.0 0.0)
46+
damping (0.0 0.0 0.0 0.0)
4747

4848
[LIMITS]
49-
jntPosMax 17.0 20.0 45.0 30.0
50-
jntPosMin -30.0 -20.0 -45.0 -30
51-
jntVelMax 100.0 100.0 100.0 100
49+
jntPosMax (17.0 20.0 45.0 30.0)
50+
jntPosMin (-30.0 -20.0 -45.0 -30)
51+
jntVelMax (100.0 100.0 100.0 100)
+29-29
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,13 @@
11
disableImplicitNetworkWrapper
22
yarpDeviceName left_arm_hardware_device
33

4-
jointNames l_shoulder_pitch l_shoulder_roll l_shoulder_yaw l_elbow l_wrist_yaw l_wrist_roll l_wrist_pitch
4+
jointNames (l_shoulder_pitch l_shoulder_roll l_shoulder_yaw l_elbow l_wrist_yaw l_wrist_roll l_wrist_pitch)
55

6-
min_stiffness 0.0 0.0 0.0 0.0 0.0 0.0 0.0
7-
max_stiffness 1000.0 1000.0 1000.0 1000.0 1000.0 1000.0 1000.0
8-
min_damping 0.0 0.0 0.0 0.0 0.0 0.0 0.0
9-
max_damping 100.0 100.0 100.0 100.0 100.0 100.0 100.0
10-
max_torques 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0
6+
min_stiffness (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
7+
max_stiffness (1000.0 1000.0 1000.0 1000.0 1000.0 1000.0 1000.0)
8+
min_damping (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
9+
max_damping (100.0 100.0 100.0 100.0 100.0 100.0 100.0)
10+
max_torques (1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0 1000000.0)
1111

1212
[TRAJECTORY_GENERATION]
1313
trajectory_type minimum_jerk
@@ -17,37 +17,37 @@ trajectory_type minimum_jerk
1717
[POSITION_CONTROL]
1818
controlUnits metric_units
1919
controlLaw joint_pid_gazebo_v1
20-
kp 5.745 5.745 5.745 1.745 1.745 1.745 1.745
21-
kd 0.174 0.174 0.174 0.174 0.174 0.174 0.0
22-
ki 0.174 0.174 0.174 0.174 0.174 0.174 0.0
23-
maxInt 9999 9999 9999 9999 9999 9999 9999
24-
maxOutput 9999 9999 9999 9999 9999 9999 9999
25-
shift 0.0 0.0 0.0 0.0 0.0 0.0 0.0
26-
ko 0.0 0.0 0.0 0.0 0.0 0.0 0.0
27-
stictionUp 0.0 0.0 0.0 0.0 0.0 0.0 0.0
28-
stictionDwn 0.0 0.0 0.0 0.0 0.0 0.0 0.0
20+
kp (5.745 5.745 5.745 1.745 1.745 1.745 1.745)
21+
kd (0.174 0.174 0.174 0.174 0.174 0.174 0.0)
22+
ki (0.174 0.174 0.174 0.174 0.174 0.174 0.0)
23+
maxInt (9999 9999 9999 9999 9999 9999 9999)
24+
maxOutput (9999 9999 9999 9999 9999 9999 9999)
25+
shift (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
26+
ko (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
27+
stictionUp (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
28+
stictionDwn (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
2929

3030
[VELOCITY_CONTROL]
3131
velocityControlImplementationType integrator_and_position_pid
3232
controlUnits metric_units
3333
controlLaw joint_pid_gazebo_v1
34-
kp 8.726 8.726 8.726 5.236 5.236 5.236 5.236
35-
kd 0.035 0.035 0.035 0.002 0.002 0.002 0.0
36-
ki 0.002 0.002 0.002 0.0 0.0 0.0 0.0
37-
maxInt 9999 9999 9999 9999 9999 9999 9999
38-
maxOutput 9999 9999 9999 9999 9999 9999 9999
39-
shift 0.0 0.0 0.0 0.0 0.0 0.0 0.0
40-
ko 0.0 0.0 0.0 0.0 0.0 0.0 0.0
41-
stictionUp 0.0 0.0 0.0 0.0 0.0 0.0 0.0
42-
stictionDwn 0.0 0.0 0.0 0.0 0.0 0.0 0.0
34+
kp (8.726 8.726 8.726 5.236 5.236 5.236 5.236)
35+
kd (0.035 0.035 0.035 0.002 0.002 0.002 0.0)
36+
ki (0.002 0.002 0.002 0.0 0.0 0.0 0.0)
37+
maxInt (9999 9999 9999 9999 9999 9999 9999)
38+
maxOutput (9999 9999 9999 9999 9999 9999 9999)
39+
shift (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
40+
ko (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
41+
stictionUp (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
42+
stictionDwn (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
4343

4444
[IMPEDANCE_CONTROL]
4545
controlUnits metric_units
4646
controlLaw joint_pid_gazebo_v1
47-
stiffness 0.0 0.0 0.0 0.0 0.0 0.0 0.0
48-
damping 0.0 0.0 0.0 0.0 0.0 0.0 0.0
47+
stiffness (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
48+
damping (0.0 0.0 0.0 0.0 0.0 0.0 0.0)
4949

5050
[LIMITS]
51-
jntPosMax 20.0 160.0 80.0 75.0 90.0 50.0 30.0
52-
jntPosMin -175.0 12.0 -50.0 -3.0 -90.0 -60.0 -30.0
53-
jntVelMax 100.0 100.0 100.0 100.0 100.0 100.0 100.0
51+
jntPosMax (20.0 160.0 80.0 75.0 90.0 50.0 30.0)
52+
jntPosMin (-175.0 12.0 -50.0 -3.0 -90.0 -60.0 -30.0)
53+
jntVelMax (100.0 100.0 100.0 100.0 100.0 100.0 100.0)
Original file line numberDiff line numberDiff line change
@@ -1,61 +1,61 @@
11
disableImplicitNetworkWrapper
22
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)
55

66
[COUPLING]
77
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)
1111

1212
[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)
2121

2222
[TRAJECTORY_GENERATION]
2323
trajectory_type minimum_jerk
2424

2525
[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)
2929

3030
[POSITION_CONTROL]
3131
controlUnits metric_units
3232
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)
4242

4343
[VELOCITY_CONTROL]
4444
controlUnits metric_units
4545
controlLaw joint_pid_gazebo_v1
4646
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)
5656

5757
[IMPEDANCE_CONTROL]
5858
controlUnits metric_units
5959
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)
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,13 @@
11
disableImplicitNetworkWrapper
22
yarpDeviceName left_hand_hardware_device
33
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
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)
55

66
[COUPLING]
77
device couplingXCubHandMk5
88
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 (100.0 90.0 15.0 90.0 90.0 90.0)
9+
actuatedAxesPosMin (0.0 0.0 0.0 0.0 0.0 0.0)
10+
actuatedAxesPosMax (100.0 90.0 15.0 90.0 90.0 90.0)
1111

1212
[COUPLING_PARAMS]
1313
L0x (-0.0050 -0.0050 -0.0050 -0.0050 -0.0050)
@@ -30,32 +30,32 @@ jntPosMin (0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0 0.0
3030
[POSITION_CONTROL]
3131
controlUnits metric_units
3232
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)
4242

4343
[VELOCITY_CONTROL]
4444
controlUnits metric_units
4545
controlLaw joint_pid_gazebo_v1
4646
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)
5656

5757
[IMPEDANCE_CONTROL]
5858
controlUnits metric_units
5959
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

Comments
 (0)