diff --git a/nao_dcm_apps/nao_dcm_gazebo/config/gazebo_ros_control_params.yaml b/nao_dcm_apps/nao_dcm_gazebo/config/gazebo_ros_control_params.yaml index 3e97ee4..d267913 100644 --- a/nao_dcm_apps/nao_dcm_gazebo/config/gazebo_ros_control_params.yaml +++ b/nao_dcm_apps/nao_dcm_gazebo/config/gazebo_ros_control_params.yaml @@ -1,52 +1,52 @@ nao_dcm/gazebo_ros_control/pid_gains: - HeadYaw: {p: 500.0, i: 1000.0, d: 0.01} + HeadYaw: {p: 1000.0, i: 100.0, d: 1.0} - HeadPitch: {p: 500.0, i: 1000.0, d: 0.01} + HeadPitch: {p: 1000.0, i: 100.0, d: 1.0} - LShoulderPitch: {p: 500.0, i: 1000.0, d: 0.01} + LShoulderPitch: {p: 100.0, i: 10.0, d: 2.0} - LElbowYaw: {p: 500.0, i: 1000.0, d: 0.01} + LElbowYaw: {p: 1000.0, i: 100.0, d: 1.0} - LElbowRoll: {p: 500.0, i: 1000.0, d: 0.01} + LElbowRoll: {p: 1000.0, i: 100.0, d: 1.0} - LShoulderRoll: {p: 500.0, i: 1000.0, d: 0.01} + LShoulderRoll: {p: 100.0, i: 10.0, d: 1.0} - LWristYaw: {p: 500.0, i: 1000.0, d: 0.01} + LWristYaw: {p: 100.0, i: 100.0, d: 1.0} - LHand: {p: 500.0, i: 1000.0, d: 0.01} + LHand: {p: 100.0, i: 100.0, d: 3.0} - RShoulderPitch: {p: 500.0, i: 1000.0, d: 0.01} + RShoulderPitch: {p: 100.0, i: 10.0, d: 2.0} - RElbowYaw: {p: 500.0, i: 1000.0, d: 0.01} + RElbowYaw: {p: 500.0, i: 100.0, d: 1.0} - RElbowRoll: {p: 500.0, i: 1000.0, d: 0.01} + RElbowRoll: {p: 500.0, i: 100.0, d: 1.0} - RShoulderRoll: {p: 500.0, i: 1000.0, d: 0.01} + RShoulderRoll: {p: 100.0, i: 10.0, d: 1.0} - RWristYaw: {p: 500.0, i: 1000.0, d: 0.01} + RWristYaw: {p: 100.0, i: 0.0, d: 1.0} - RHand: {p: 500.0, i: 1000.0, d: 0.01} + RHand: {p: 100.0, i: 100.0, d: 3.0} - LHipYawPitch: {p: 500.0, i: 1000.0, d: 0.01} + LHipYawPitch: {p: 500.0, i: 0.0, d: 0.1} - LHipRoll: {p: 500.0, i: 1000.0, d: 0.01} + LHipRoll: {p: 500.0, i: 0.0, d: 0.1} - LHipPitch: {p: 500.0, i: 1000.0, d: 0.01} + LHipPitch: {p: 500.0, i: 0.0, d: 0.1} - LKneePitch: {p: 500.0, i: 1000.0, d: 0.01} + LKneePitch: {p: 500.0, i: 0.0, d: 0.1} - LAnklePitch: {p: 500.0, i: 1000.0, d: 0.01} + LAnklePitch: {p: 500.0, i: 0.0, d: 0.1} - LAnkleRoll: {p: 500.0, i: 1000.0, d: 0.01} + LAnkleRoll: {p: 500.0, i: 0.0, d: 0.1} - RHipYawPitch: {p: 500.0, i: 1000.0, d: 0.01} + RHipYawPitch: {p: 500.0, i: 0.0, d: 0.1} - RHipRoll: {p: 500.0, i: 1000.0, d: 0.01} + RHipRoll: {p: 500.0, i: 0.0, d: 0.1} - RHipPitch: {p: 500.0, i: 1000.0, d: 0.01} + RHipPitch: {p: 500.0, i: 0.0, d: 0.1} - RKneePitch: {p: 500.0, i: 1000.0, d: 0.01} + RKneePitch: {p: 500.0, i: 0.0, d: 0.1} - RAnklePitch: {p: 500.0, i: 1000.0, d: 0.01} + RAnklePitch: {p: 500.0, i: 0.0, d: 0.1} - RAnkleRoll: {p: 500.0, i: 1000.0, d: 0.01} \ No newline at end of file + RAnkleRoll: {p: 500.0, i: 0.0, d: 0.1}