From 806548dd80762bef4ee80e402bc0e2be5b0a2cc2 Mon Sep 17 00:00:00 2001 From: Thomas Timm Andersen Date: Tue, 20 Oct 2015 14:23:15 +0200 Subject: [PATCH] Tuned PID values to work with a real robot --- config/ur10_controllers.yaml | 12 ++++++------ config/ur5_controllers.yaml | 12 ++++++------ launch/ur10_ros_control.launch | 2 +- 3 files changed, 13 insertions(+), 13 deletions(-) diff --git a/config/ur10_controllers.yaml b/config/ur10_controllers.yaml index 8c0c5bc..19e0394 100644 --- a/config/ur10_controllers.yaml +++ b/config/ur10_controllers.yaml @@ -83,12 +83,12 @@ vel_based_pos_traj_controller: action_monitor_rate: 10 gains: #!!These values are useable, but maybe not optimal - shoulder_pan_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - shoulder_lift_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - elbow_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - wrist_1_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - wrist_2_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - wrist_3_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} + shoulder_pan_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + shoulder_lift_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + elbow_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + wrist_1_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + wrist_2_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + wrist_3_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} # state_publish_rate: 50 # Defaults to 50 diff --git a/config/ur5_controllers.yaml b/config/ur5_controllers.yaml index a1054b7..4eab52e 100644 --- a/config/ur5_controllers.yaml +++ b/config/ur5_controllers.yaml @@ -83,12 +83,12 @@ vel_based_pos_traj_controller: action_monitor_rate: 10 gains: #!!These values are useable, but maybe not optimal - shoulder_pan_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - shoulder_lift_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - elbow_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - wrist_1_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - wrist_2_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} - wrist_3_joint: {p: 20.0, i: 0.0, d: 0.7, i_clamp: 1} + shoulder_pan_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + shoulder_lift_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + elbow_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + wrist_1_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + wrist_2_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} + wrist_3_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} # state_publish_rate: 50 # Defaults to 50 # action_monitor_rate: 20 # Defaults to 20 diff --git a/launch/ur10_ros_control.launch b/launch/ur10_ros_control.launch index d60d02f..ce6c1e1 100644 --- a/launch/ur10_ros_control.launch +++ b/launch/ur10_ros_control.launch @@ -25,7 +25,7 @@ - +