Even more stable PID values. Credits to M. Arguedas
This commit is contained in:
parent
807cb7be49
commit
eeab4cb777
@ -3,27 +3,27 @@ nao_dcm/gazebo_ros_control/pid_gains:
|
|||||||
|
|
||||||
HeadPitch: {p: 1000.0, i: 100.0, d: 1.0}
|
HeadPitch: {p: 1000.0, i: 100.0, d: 1.0}
|
||||||
|
|
||||||
LShoulderPitch: {p: 100.0, i: 10.0, d: 2.0}
|
LShoulderPitch: {p: 80.0, i: 4.0, d: 2.0}
|
||||||
|
|
||||||
LElbowYaw: {p: 1000.0, i: 100.0, d: 1.0}
|
LElbowYaw: {p: 110.0, i: 0.0, d: 0.0}
|
||||||
|
|
||||||
LElbowRoll: {p: 1000.0, i: 100.0, d: 1.0}
|
LElbowRoll: {p: 30.0, i: 0.7, d: 0.3}
|
||||||
|
|
||||||
LShoulderRoll: {p: 100.0, i: 10.0, d: 1.0}
|
LShoulderRoll: {p: 50.0, i: 5.0, d: 0.7}
|
||||||
|
|
||||||
LWristYaw: {p: 100.0, i: 100.0, d: 1.0}
|
LWristYaw: {p: 1.0, i: 0.13, d: 0.01}
|
||||||
|
|
||||||
LHand: {p: 100.0, i: 100.0, d: 3.0}
|
LHand: {p: 100.0, i: 100.0, d: 3.0}
|
||||||
|
|
||||||
RShoulderPitch: {p: 100.0, i: 10.0, d: 2.0}
|
RShoulderPitch: {p: 80.0, i: 4.0, d: 2.0}
|
||||||
|
|
||||||
RElbowYaw: {p: 500.0, i: 100.0, d: 1.0}
|
RElbowYaw: {p: 110.0, i: 0.0, d: 0.0}
|
||||||
|
|
||||||
RElbowRoll: {p: 500.0, i: 100.0, d: 1.0}
|
RElbowRoll: {p: 30.0, i: 0.7, d: 0.3}
|
||||||
|
|
||||||
RShoulderRoll: {p: 100.0, i: 10.0, d: 1.0}
|
RShoulderRoll: {p: 50.0, i: 5.0, d: 0.7}
|
||||||
|
|
||||||
RWristYaw: {p: 100.0, i: 0.0, d: 1.0}
|
RWristYaw: {p: 1.0, i: 0.13, d: 0.01}
|
||||||
|
|
||||||
RHand: {p: 100.0, i: 100.0, d: 3.0}
|
RHand: {p: 100.0, i: 100.0, d: 3.0}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user