1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

Add velocity feedforward and reduce PID gains for UR10 joint trajectory controller (#228)

This commit is contained in:
Miguel Prada
2018-11-05 16:21:19 +01:00
committed by G.A. vd. Hoorn
parent 2f1251c2eb
commit 1b1972891c

View File

@@ -49,7 +49,7 @@ pos_based_pos_traj_controller:
# state_publish_rate: 50 # Defaults to 50 # state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20 # action_monitor_rate: 20 # Defaults to 20
#hold_trajectory_duration: 0 # Defaults to 0.5 #hold_trajectory_duration: 0 # Defaults to 0.5
# Joint Trajectory Controller ------------------------------- # Joint Trajectory Controller -------------------------------
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller # For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
vel_based_pos_traj_controller: vel_based_pos_traj_controller:
@@ -74,14 +74,22 @@ vel_based_pos_traj_controller:
state_publish_rate: 125 state_publish_rate: 125
action_monitor_rate: 10 action_monitor_rate: 10
gains: gains:
#!!These values are useable, but maybe not optimal #!!These values have not been optimized!!
shoulder_pan_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
shoulder_lift_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
elbow_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_1_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_2_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
wrist_3_joint: {p: 20.0, i: 0.0, d: 0.1, i_clamp: 1} wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
# Use a feedforward term to reduce the size of PID gains
velocity_ff:
shoulder_pan_joint: 1.0
shoulder_lift_joint: 1.0
elbow_joint: 1.0
wrist_1_joint: 1.0
wrist_2_joint: 1.0
wrist_3_joint: 1.0
# state_publish_rate: 50 # Defaults to 50 # state_publish_rate: 50 # Defaults to 50
# action_monitor_rate: 20 # Defaults to 20 # action_monitor_rate: 20 # Defaults to 20